MEKF invalid handling fix #514
31
CHANGELOG.md
31
CHANGELOG.md
@ -16,13 +16,40 @@ will consitute of a breaking change warranting a new major release:
|
||||
|
||||
# [unreleased]
|
||||
|
||||
## Fixed
|
||||
|
||||
- PAPB busy polling now implemented properly with an upper bound of how often the PAPB is allowed
|
||||
to be busy before returning the BUSY returnvalue. Also propagate and check for that case properly.
|
||||
Ideally, this will never be an issue and the PAPB VC interface should never block for a longer
|
||||
period.
|
||||
- The `mekfInvalidCounter` now resets on setting the STR to faulty.
|
||||
|
||||
## Added
|
||||
|
||||
- The event `MEKF_RECOVERY` will be triggered in case the `MEKF` does manage to recover itself.
|
||||
- The persistent TM stores now have low priorities and behave like background threads now. This
|
||||
should prevent them from blocking or slowing down the system even during dumps
|
||||
(at least in theory).
|
||||
- STR: Fix weird issues on datalink layer data reception which sometimes occur.
|
||||
- Syrlinks FDIR: Fully allow FDIR to do more recoveries. Assembly should take care of preventing
|
||||
the switch to go off.
|
||||
|
||||
## Fixed
|
||||
## Changed
|
||||
|
||||
- The `mekfInvalidCounter` now resets on setting the STR to faulty.
|
||||
- Rework FSFW OSALs to properly support regular scheduling (NICE priorities) and real-time
|
||||
scheduling.
|
||||
- STR: Move datalink layer to `StrComHandler` completely. DLL is now completely hidden from
|
||||
device handler.
|
||||
- STR: Is now scheduled twice in ACS PST.
|
||||
- `StrHelper` renamed to `StrComHandler`, is now a `DeviceHandlerIF` directly and does not wrap
|
||||
a separate UART COM interface anymore.
|
||||
- TCS: Local pool variables are members now.
|
||||
- Syrlinks: Create dedicated COM helper which uses a ring buffer to parse the Syrlinks datalinklayer
|
||||
and should make communication more reliable even on high CPU loads.
|
||||
- Syrlinks: Two communication cycles per PST.
|
||||
- Fine-tuning of various task priorities.
|
||||
- The CSP router now is scheduled with the `SCHED_RR` policy and the same priority as the PCDU
|
||||
handlers as well.
|
||||
|
||||
# [v1.39.1] 2023-03-22
|
||||
|
||||
|
@ -1,7 +1,7 @@
|
||||
/**
|
||||
* @brief Auto-generated event translation file. Contains 280 translations.
|
||||
* @brief Auto-generated event translation file. Contains 279 translations.
|
||||
* @details
|
||||
* Generated on: 2023-03-23 10:28:33
|
||||
* Generated on: 2023-03-24 14:59:06
|
||||
*/
|
||||
#include "translateEvents.h"
|
||||
|
||||
@ -173,7 +173,7 @@ const char *FIRMWARE_UPDATE_SUCCESSFUL_STRING = "FIRMWARE_UPDATE_SUCCESSFUL";
|
||||
const char *FIRMWARE_UPDATE_FAILED_STRING = "FIRMWARE_UPDATE_FAILED";
|
||||
const char *STR_HELPER_READING_REPLY_FAILED_STRING = "STR_HELPER_READING_REPLY_FAILED";
|
||||
const char *STR_HELPER_COM_ERROR_STRING = "STR_HELPER_COM_ERROR";
|
||||
const char *STR_HELPER_NO_REPLY_STRING = "STR_HELPER_NO_REPLY";
|
||||
const char *STR_COM_REPLY_TIMEOUT_STRING = "STR_COM_REPLY_TIMEOUT";
|
||||
const char *STR_HELPER_DEC_ERROR_STRING = "STR_HELPER_DEC_ERROR";
|
||||
const char *POSITION_MISMATCH_STRING = "POSITION_MISMATCH";
|
||||
const char *STR_HELPER_FILE_NOT_EXISTS_STRING = "STR_HELPER_FILE_NOT_EXISTS";
|
||||
@ -620,16 +620,16 @@ const char *translateEvents(Event event) {
|
||||
case (12510):
|
||||
return STR_HELPER_COM_ERROR_STRING;
|
||||
case (12511):
|
||||
return STR_HELPER_NO_REPLY_STRING;
|
||||
case (12512):
|
||||
return STR_HELPER_DEC_ERROR_STRING;
|
||||
return STR_COM_REPLY_TIMEOUT_STRING;
|
||||
case (12513):
|
||||
return POSITION_MISMATCH_STRING;
|
||||
return STR_HELPER_DEC_ERROR_STRING;
|
||||
case (12514):
|
||||
return STR_HELPER_FILE_NOT_EXISTS_STRING;
|
||||
return POSITION_MISMATCH_STRING;
|
||||
case (12515):
|
||||
return STR_HELPER_SENDING_PACKET_FAILED_STRING;
|
||||
return STR_HELPER_FILE_NOT_EXISTS_STRING;
|
||||
case (12516):
|
||||
return STR_HELPER_SENDING_PACKET_FAILED_STRING;
|
||||
case (12517):
|
||||
return STR_HELPER_REQUESTING_MSG_FAILED_STRING;
|
||||
case (12600):
|
||||
return MPSOC_FLASH_WRITE_FAILED_STRING;
|
||||
|
@ -2,7 +2,7 @@
|
||||
* @brief Auto-generated object translation file.
|
||||
* @details
|
||||
* Contains 169 translations.
|
||||
* Generated on: 2023-03-21 23:59:36
|
||||
* Generated on: 2023-03-24 14:59:06
|
||||
*/
|
||||
#include "translateObjects.h"
|
||||
|
||||
@ -50,7 +50,7 @@ const char *PLPCDU_HANDLER_STRING = "PLPCDU_HANDLER";
|
||||
const char *RAD_SENSOR_STRING = "RAD_SENSOR";
|
||||
const char *PLOC_UPDATER_STRING = "PLOC_UPDATER";
|
||||
const char *PLOC_MEMORY_DUMPER_STRING = "PLOC_MEMORY_DUMPER";
|
||||
const char *STR_HELPER_STRING = "STR_HELPER";
|
||||
const char *STR_COM_IF_STRING = "STR_COM_IF";
|
||||
const char *PLOC_MPSOC_HELPER_STRING = "PLOC_MPSOC_HELPER";
|
||||
const char *AXI_PTME_CONFIG_STRING = "AXI_PTME_CONFIG";
|
||||
const char *PTME_CONFIG_STRING = "PTME_CONFIG";
|
||||
@ -86,6 +86,7 @@ const char *RTD_13_IC16_PLPCDU_HEATSPREADER_STRING = "RTD_13_IC16_PLPCDU_HEATSPR
|
||||
const char *RTD_14_IC17_TCS_BOARD_STRING = "RTD_14_IC17_TCS_BOARD";
|
||||
const char *RTD_15_IC18_IMTQ_STRING = "RTD_15_IC18_IMTQ";
|
||||
const char *SYRLINKS_HANDLER_STRING = "SYRLINKS_HANDLER";
|
||||
const char *SYRLINKS_COM_HANDLER_STRING = "SYRLINKS_COM_HANDLER";
|
||||
const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF";
|
||||
const char *DUMMY_COM_IF_STRING = "DUMMY_COM_IF";
|
||||
const char *SCEX_UART_READER_STRING = "SCEX_UART_READER";
|
||||
@ -171,7 +172,6 @@ const char *LOG_STORE_AND_TM_TASK_STRING = "LOG_STORE_AND_TM_TASK";
|
||||
const char *HK_STORE_AND_TM_TASK_STRING = "HK_STORE_AND_TM_TASK";
|
||||
const char *CFDP_STORE_AND_TM_TASK_STRING = "CFDP_STORE_AND_TM_TASK";
|
||||
const char *DOWNLINK_RAM_STORE_STRING = "DOWNLINK_RAM_STORE";
|
||||
const char *CCSDS_IP_CORE_BRIDGE_STRING = "CCSDS_IP_CORE_BRIDGE";
|
||||
const char *THERMAL_TEMP_INSERTER_STRING = "THERMAL_TEMP_INSERTER";
|
||||
const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE";
|
||||
const char *NO_OBJECT_STRING = "NO_OBJECT";
|
||||
@ -267,7 +267,7 @@ const char *translateObject(object_id_t object) {
|
||||
case 0x44330001:
|
||||
return PLOC_MEMORY_DUMPER_STRING;
|
||||
case 0x44330002:
|
||||
return STR_HELPER_STRING;
|
||||
return STR_COM_IF_STRING;
|
||||
case 0x44330003:
|
||||
return PLOC_MPSOC_HELPER_STRING;
|
||||
case 0x44330004:
|
||||
@ -338,6 +338,8 @@ const char *translateObject(object_id_t object) {
|
||||
return RTD_15_IC18_IMTQ_STRING;
|
||||
case 0x445300A3:
|
||||
return SYRLINKS_HANDLER_STRING;
|
||||
case 0x445300A4:
|
||||
return SYRLINKS_COM_HANDLER_STRING;
|
||||
case 0x49000001:
|
||||
return ARDUINO_COM_IF_STRING;
|
||||
case 0x49000002:
|
||||
@ -508,8 +510,6 @@ const char *translateObject(object_id_t object) {
|
||||
return CFDP_STORE_AND_TM_TASK_STRING;
|
||||
case 0x73040004:
|
||||
return DOWNLINK_RAM_STORE_STRING;
|
||||
case 0x73500000:
|
||||
return CCSDS_IP_CORE_BRIDGE_STRING;
|
||||
case 0x90000003:
|
||||
return THERMAL_TEMP_INSERTER_STRING;
|
||||
case 0xCAFECAFE:
|
||||
|
@ -12,7 +12,6 @@ target_sources(${OBSW_NAME} PUBLIC main.cpp obsw.cpp)
|
||||
add_subdirectory(boardtest)
|
||||
|
||||
add_subdirectory(boardconfig)
|
||||
add_subdirectory(comIF)
|
||||
add_subdirectory(core)
|
||||
|
||||
if(EIVE_Q7S_EM)
|
||||
|
@ -14,7 +14,6 @@
|
||||
/*******************************************************************/
|
||||
|
||||
#define OBSW_ENABLE_PERIODIC_HK 0
|
||||
#define OBSW_ENABLE_SYRLINKS_TRANSMIT_TIMEOUT 0
|
||||
// This switch will cause the SW to command the EIVE system object to safe mode. This will
|
||||
// trigger a lot of events, so it can make sense to disable this for debugging purposes
|
||||
#define OBSW_COMMAND_SAFE_MODE_AT_STARTUP 1
|
||||
|
@ -1 +0,0 @@
|
||||
target_sources(${OBSW_NAME} PRIVATE)
|
@ -4,6 +4,8 @@
|
||||
#include <linux/devices/AcsBoardPolling.h>
|
||||
#include <linux/devices/ImtqPollingTask.h>
|
||||
#include <linux/devices/RwPollingTask.h>
|
||||
#include <linux/devices/SyrlinksComHandler.h>
|
||||
#include <linux/devices/startracker/StrComHandler.h>
|
||||
#include <mission/devices/GyrL3gCustomHandler.h>
|
||||
#include <mission/devices/MgmLis3CustomHandler.h>
|
||||
#include <mission/devices/MgmRm3100CustomHandler.h>
|
||||
@ -45,7 +47,6 @@
|
||||
#include "linux/devices/ploc/PlocMemoryDumper.h"
|
||||
#include "linux/devices/ploc/PlocSupervisorHandler.h"
|
||||
#include "linux/devices/startracker/StarTrackerHandler.h"
|
||||
#include "linux/devices/startracker/StrHelper.h"
|
||||
#include "linux/ipcore/AxiPtmeConfig.h"
|
||||
#include "linux/ipcore/PapbVcInterface.h"
|
||||
#include "linux/ipcore/PdecHandler.h"
|
||||
@ -179,7 +180,7 @@ void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF,
|
||||
*gpioComIF = new LinuxLibgpioIF(objects::GPIO_IF);
|
||||
|
||||
/* Communication interfaces */
|
||||
new CspComIF(objects::CSP_COM_IF);
|
||||
new CspComIF(objects::CSP_COM_IF, "CSP_ROUTER", 60);
|
||||
*i2cComIF = new I2cComIF(objects::I2C_COM_IF);
|
||||
*uartComIF = new SerialComIF(objects::UART_COM_IF);
|
||||
*spiMainComIF = new SpiComIF(objects::SPI_MAIN_COM_IF, q7s::SPI_DEFAULT_DEV, **gpioComIF);
|
||||
@ -592,16 +593,17 @@ void ObjectFactory::createSolarArrayDeploymentComponents(PowerSwitchIF& pwrSwitc
|
||||
|
||||
void ObjectFactory::createSyrlinksComponents(PowerSwitchIF* pwrSwitcher) {
|
||||
auto* syrlinksUartCookie =
|
||||
new SerialCookie(objects::SYRLINKS_HANDLER, q7s::UART_SYRLINKS_DEV, uart::SYRLINKS_BAUD,
|
||||
new SerialCookie(objects::SYRLINKS_HANDLER, q7s::UART_SYRLINKS_DEV, serial::SYRLINKS_BAUD,
|
||||
syrlinks::MAX_REPLY_SIZE, UartModes::NON_CANONICAL);
|
||||
syrlinksUartCookie->setParityEven();
|
||||
|
||||
new SyrlinksComHandler(objects::SYRLINKS_COM_HANDLER);
|
||||
auto* syrlinksAssy = new SyrlinksAssembly(objects::SYRLINKS_ASSY);
|
||||
syrlinksAssy->connectModeTreeParent(satsystem::com::SUBSYSTEM);
|
||||
auto syrlinksFdir = new SyrlinksFdir(objects::SYRLINKS_HANDLER);
|
||||
auto syrlinksHandler =
|
||||
new SyrlinksHandler(objects::SYRLINKS_HANDLER, objects::UART_COM_IF, syrlinksUartCookie,
|
||||
pcdu::PDU1_CH1_SYRLINKS_12V, syrlinksFdir);
|
||||
new SyrlinksHandler(objects::SYRLINKS_HANDLER, objects::SYRLINKS_COM_HANDLER,
|
||||
syrlinksUartCookie, pcdu::PDU1_CH1_SYRLINKS_12V, syrlinksFdir);
|
||||
syrlinksHandler->setPowerSwitcher(pwrSwitcher);
|
||||
syrlinksHandler->connectModeTreeParent(*syrlinksAssy);
|
||||
#if OBSW_DEBUG_SYRLINKS == 1
|
||||
@ -623,8 +625,8 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwit
|
||||
mpsocGpioCookie->addGpio(gpioIds::ENABLE_MPSOC_UART, gpioConfigMPSoC);
|
||||
gpioChecker(gpioComIF->addGpios(mpsocGpioCookie), "PLOC MPSoC");
|
||||
auto mpsocCookie =
|
||||
new SerialCookie(objects::PLOC_MPSOC_HANDLER, q7s::UART_PLOC_MPSOC_DEV, uart::PLOC_MPSOC_BAUD,
|
||||
mpsoc::MAX_REPLY_SIZE, UartModes::NON_CANONICAL);
|
||||
new SerialCookie(objects::PLOC_MPSOC_HANDLER, q7s::UART_PLOC_MPSOC_DEV,
|
||||
serial::PLOC_MPSOC_BAUD, mpsoc::MAX_REPLY_SIZE, UartModes::NON_CANONICAL);
|
||||
mpsocCookie->setNoFixedSizeReply();
|
||||
auto plocMpsocHelper = new PlocMPSoCHelper(objects::PLOC_MPSOC_HELPER);
|
||||
auto* mpsocHandler = new PlocMPSoCHandler(
|
||||
@ -639,9 +641,9 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwit
|
||||
auto supvGpioCookie = new GpioCookie;
|
||||
supvGpioCookie->addGpio(gpioIds::ENABLE_SUPV_UART, gpioConfigSupv);
|
||||
gpioComIF->addGpios(supvGpioCookie);
|
||||
auto supervisorCookie =
|
||||
new SerialCookie(objects::PLOC_SUPERVISOR_HANDLER, q7s::UART_PLOC_SUPERVSIOR_DEV,
|
||||
uart::PLOC_SUPV_BAUD, supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL);
|
||||
auto supervisorCookie = new SerialCookie(objects::PLOC_SUPERVISOR_HANDLER,
|
||||
q7s::UART_PLOC_SUPERVSIOR_DEV, serial::PLOC_SUPV_BAUD,
|
||||
supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL);
|
||||
supervisorCookie->setNoFixedSizeReply();
|
||||
auto supvHelper = new PlocSupvUartManager(objects::PLOC_SUPERVISOR_HELPER);
|
||||
auto* supvHandler = new PlocSupervisorHandler(objects::PLOC_SUPERVISOR_HANDLER, supervisorCookie,
|
||||
@ -934,10 +936,10 @@ void ObjectFactory::createStrComponents(PowerSwitchIF* pwrSwitcher) {
|
||||
auto* strAssy = new StrAssembly(objects::STR_ASSY);
|
||||
strAssy->connectModeTreeParent(satsystem::acs::ACS_SUBSYSTEM);
|
||||
auto* starTrackerCookie =
|
||||
new SerialCookie(objects::STAR_TRACKER, q7s::UART_STAR_TRACKER_DEV, uart::STAR_TRACKER_BAUD,
|
||||
new SerialCookie(objects::STAR_TRACKER, q7s::UART_STAR_TRACKER_DEV, serial::STAR_TRACKER_BAUD,
|
||||
startracker::MAX_FRAME_SIZE * 2 + 2, UartModes::NON_CANONICAL);
|
||||
starTrackerCookie->setNoFixedSizeReply();
|
||||
StrHelper* strHelper = new StrHelper(objects::STR_HELPER);
|
||||
StrComHandler* strComIF = new StrComHandler(objects::STR_COM_IF);
|
||||
|
||||
const char* paramJsonFile = nullptr;
|
||||
#ifdef EGSE
|
||||
@ -954,8 +956,8 @@ void ObjectFactory::createStrComponents(PowerSwitchIF* pwrSwitcher) {
|
||||
}
|
||||
auto strFdir = new StrFdir(objects::STAR_TRACKER);
|
||||
auto starTracker =
|
||||
new StarTrackerHandler(objects::STAR_TRACKER, objects::UART_COM_IF, starTrackerCookie,
|
||||
paramJsonFile, strHelper, pcdu::PDU1_CH2_STAR_TRACKER_5V);
|
||||
new StarTrackerHandler(objects::STAR_TRACKER, objects::STR_COM_IF, starTrackerCookie,
|
||||
paramJsonFile, strComIF, pcdu::PDU1_CH2_STAR_TRACKER_5V);
|
||||
starTracker->setPowerSwitcher(pwrSwitcher);
|
||||
starTracker->connectModeTreeParent(*strAssy);
|
||||
starTracker->setCustomFdir(strFdir);
|
||||
|
@ -72,8 +72,9 @@ void scheduling::initTasks() {
|
||||
#if OBSW_ADD_SA_DEPL == 1
|
||||
// Could add this to the core controller but the core controller does so many thing that I would
|
||||
// prefer to have the solar array deployment in a seprate task.
|
||||
PeriodicTaskIF* solarArrayDeplTask = factory->createPeriodicTask(
|
||||
"SOLAR_ARRAY_DEPL", 65, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc);
|
||||
PeriodicTaskIF* solarArrayDeplTask =
|
||||
factory->createPeriodicTask("SOLAR_ARRAY_DEPL", 65, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4,
|
||||
missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = solarArrayDeplTask->addComponent(objects::SOLAR_ARRAY_DEPL_HANDLER);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("SOLAR_ARRAY_DEPL", objects::SOLAR_ARRAY_DEPL_HANDLER);
|
||||
@ -81,7 +82,7 @@ void scheduling::initTasks() {
|
||||
#endif
|
||||
|
||||
PeriodicTaskIF* coreCtrlTask = factory->createPeriodicTask(
|
||||
"CORE_CTRL", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc);
|
||||
"CORE_CTRL", 55, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = coreCtrlTask->addComponent(objects::CORE_CONTROLLER);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("CORE_CTRL", objects::CORE_CONTROLLER);
|
||||
@ -89,7 +90,7 @@ void scheduling::initTasks() {
|
||||
|
||||
/* TMTC Distribution */
|
||||
PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask(
|
||||
"DIST", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
||||
"TC_DIST", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc, &RR_SCHEDULING);
|
||||
#if OBSW_ADD_TCPIP_SERVERS == 1
|
||||
#if OBSW_ADD_TMTC_UDP_SERVER == 1
|
||||
result = tmTcDistributor->addComponent(objects::UDP_TMTC_SERVER);
|
||||
@ -120,7 +121,7 @@ void scheduling::initTasks() {
|
||||
#if OBSW_ADD_TCPIP_SERVERS == 1
|
||||
#if OBSW_ADD_TMTC_UDP_SERVER == 1
|
||||
PeriodicTaskIF* udpPollingTask = factory->createPeriodicTask(
|
||||
"UDP_TMTC_POLLING", 65, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
||||
"UDP_TMTC_POLLING", 0, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
||||
result = udpPollingTask->addComponent(objects::UDP_TMTC_POLLING_TASK);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("UDP_POLLING", objects::UDP_TMTC_POLLING_TASK);
|
||||
@ -128,7 +129,7 @@ void scheduling::initTasks() {
|
||||
#endif
|
||||
#if OBSW_ADD_TMTC_TCP_SERVER == 1
|
||||
PeriodicTaskIF* tcpPollingTask = factory->createPeriodicTask(
|
||||
"TCP_TMTC_POLLING", 65, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
||||
"TCP_TMTC_POLLING", 0, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
||||
result = tcpPollingTask->addComponent(objects::TCP_TMTC_POLLING_TASK);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("UDP_POLLING", objects::TCP_TMTC_POLLING_TASK);
|
||||
@ -136,8 +137,9 @@ void scheduling::initTasks() {
|
||||
#endif
|
||||
#endif
|
||||
|
||||
PeriodicTaskIF* genericSysTask = factory->createPeriodicTask(
|
||||
"SYSTEM_TASK", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.5, missedDeadlineFunc);
|
||||
PeriodicTaskIF* genericSysTask =
|
||||
factory->createPeriodicTask("SYSTEM_TASK", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.5,
|
||||
missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = genericSysTask->addComponent(objects::EIVE_SYSTEM);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("EIVE_SYSTEM", objects::EIVE_SYSTEM);
|
||||
@ -171,7 +173,7 @@ void scheduling::initTasks() {
|
||||
|
||||
// Runs in IRQ mode, frequency does not really matter
|
||||
PeriodicTaskIF* pdecHandlerTask = factory->createPeriodicTask(
|
||||
"PDEC_HANDLER", 75, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc);
|
||||
"PDEC_HANDLER", 75, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr, &RR_SCHEDULING);
|
||||
result = pdecHandlerTask->addComponent(objects::PDEC_HANDLER);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("PDEC Handler", objects::PDEC_HANDLER);
|
||||
@ -179,50 +181,54 @@ void scheduling::initTasks() {
|
||||
|
||||
#endif /* OBSW_ADD_CCSDS_IP_CORE == 1 */
|
||||
// All the TM store tasks run in permanent loops, frequency does not matter
|
||||
PeriodicTaskIF* liveTmTask =
|
||||
factory->createPeriodicTask("LIVE_TM", 55, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr);
|
||||
PeriodicTaskIF* liveTmTask = factory->createPeriodicTask(
|
||||
"LIVE_TM", 55, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr, &RR_SCHEDULING);
|
||||
result = liveTmTask->addComponent(objects::LIVE_TM_TASK);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("LIVE_TM", objects::LIVE_TM_TASK);
|
||||
}
|
||||
PeriodicTaskIF* logTmTask = factory->createPeriodicTask(
|
||||
"LOG_STORE_AND_TM", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr);
|
||||
"LOG_PSTORE", 0, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr);
|
||||
result = logTmTask->addComponent(objects::LOG_STORE_AND_TM_TASK);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("LOG_STORE_AND_TM", objects::LOG_STORE_AND_TM_TASK);
|
||||
}
|
||||
PeriodicTaskIF* hkTmTask = factory->createPeriodicTask(
|
||||
"HK_STORE_AND_TM", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr);
|
||||
"HK_PSTORE", 0, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr);
|
||||
result = hkTmTask->addComponent(objects::HK_STORE_AND_TM_TASK);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("HK_STORE_AND_TM", objects::HK_STORE_AND_TM_TASK);
|
||||
}
|
||||
PeriodicTaskIF* cfdpTmTask = factory->createPeriodicTask(
|
||||
"CFDP_STORE_AND_TM", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr);
|
||||
"CFDP_PSTORE", 0, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, nullptr);
|
||||
result = cfdpTmTask->addComponent(objects::CFDP_STORE_AND_TM_TASK);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("CFDP_STORE_AND_TM", objects::CFDP_STORE_AND_TM_TASK);
|
||||
}
|
||||
|
||||
// TODO: Use user priorities for this task.
|
||||
#if OBSW_ADD_CFDP_COMPONENTS == 1
|
||||
PeriodicTaskIF* cfdpTask = factory->createPeriodicTask(
|
||||
"CFDP Handler", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc);
|
||||
PeriodicTaskIF* cfdpTask =
|
||||
factory->createPeriodicTask("CFDP_HANDLER", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4,
|
||||
missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = cfdpTask->addComponent(objects::CFDP_HANDLER);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("CFDP Handler", objects::CFDP_HANDLER);
|
||||
scheduling::printAddObjectError("CFDP", objects::CFDP_HANDLER);
|
||||
}
|
||||
#endif
|
||||
|
||||
PeriodicTaskIF* gpsTask = factory->createPeriodicTask(
|
||||
"GPS_TASK", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc);
|
||||
PeriodicTaskIF* gpsTask =
|
||||
factory->createPeriodicTask("GPS_TASK", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4,
|
||||
missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = gpsTask->addComponent(objects::GPS_CONTROLLER);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("GPS_CTRL", objects::GPS_CONTROLLER);
|
||||
}
|
||||
|
||||
#if OBSW_ADD_ACS_BOARD == 1
|
||||
PeriodicTaskIF* acsBrdPolling = factory->createPeriodicTask(
|
||||
"ACS_BOARD_POLLING", 85, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc);
|
||||
PeriodicTaskIF* acsBrdPolling =
|
||||
factory->createPeriodicTask("ACS_BOARD_POLLING", 85, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2,
|
||||
0.4, missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = acsBrdPolling->addComponent(objects::ACS_BOARD_POLLING_TASK);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("ACS_BOARD_POLLING", objects::ACS_BOARD_POLLING_TASK);
|
||||
@ -230,16 +236,18 @@ void scheduling::initTasks() {
|
||||
#endif
|
||||
|
||||
#if OBSW_ADD_RW == 1
|
||||
PeriodicTaskIF* rwPolling = factory->createPeriodicTask(
|
||||
"RW_POLLING_TASK", 85, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc);
|
||||
PeriodicTaskIF* rwPolling =
|
||||
factory->createPeriodicTask("RW_POLLING_TASK", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2,
|
||||
0.4, missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = rwPolling->addComponent(objects::RW_POLLING_TASK);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("RW_POLLING_TASK", objects::RW_POLLING_TASK);
|
||||
}
|
||||
#endif
|
||||
#if OBSW_ADD_MGT == 1
|
||||
PeriodicTaskIF* imtqPolling = factory->createPeriodicTask(
|
||||
"IMTQ_POLLING_TASK", 85, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc);
|
||||
PeriodicTaskIF* imtqPolling =
|
||||
factory->createPeriodicTask("IMTQ_POLLING_TASK", 85, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2,
|
||||
0.4, missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = imtqPolling->addComponent(objects::IMTQ_POLLING);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("IMTQ_POLLING_TASK", objects::IMTQ_POLLING);
|
||||
@ -247,16 +255,18 @@ void scheduling::initTasks() {
|
||||
#endif
|
||||
|
||||
#if OBSW_ADD_SUN_SENSORS == 1
|
||||
PeriodicTaskIF* susPolling = factory->createPeriodicTask(
|
||||
"SUS_POLLING_TASK", 85, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc);
|
||||
PeriodicTaskIF* susPolling =
|
||||
factory->createPeriodicTask("SUS_POLLING_TASK", 85, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2,
|
||||
0.4, missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = susPolling->addComponent(objects::SUS_POLLING_TASK);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("SUS_POLLING_TASK", objects::SUS_POLLING_TASK);
|
||||
}
|
||||
#endif
|
||||
|
||||
PeriodicTaskIF* acsSysTask = factory->createPeriodicTask(
|
||||
"ACS_SYS_TASK", 55, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc);
|
||||
PeriodicTaskIF* acsSysTask =
|
||||
factory->createPeriodicTask("ACS_SYS_TASK", 55, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4,
|
||||
missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = acsSysTask->addComponent(objects::ACS_SUBSYSTEM);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("ACS_SUBSYSTEM", objects::ACS_SUBSYSTEM);
|
||||
@ -283,7 +293,7 @@ void scheduling::initTasks() {
|
||||
}
|
||||
|
||||
PeriodicTaskIF* tcsSystemTask = factory->createPeriodicTask(
|
||||
"TCS_TASK", 55, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.5, missedDeadlineFunc);
|
||||
"TCS_TASK", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.5, missedDeadlineFunc, &RR_SCHEDULING);
|
||||
scheduling::scheduleRtdSensors(tcsSystemTask);
|
||||
result = tcsSystemTask->addComponent(objects::TCS_SUBSYSTEM);
|
||||
if (result != returnvalue::OK) {
|
||||
@ -306,27 +316,42 @@ void scheduling::initTasks() {
|
||||
}
|
||||
#endif
|
||||
|
||||
#if OBSW_ADD_STAR_TRACKER == 1
|
||||
PeriodicTaskIF* strHelperTask = factory->createPeriodicTask(
|
||||
"STR_HELPER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
||||
result = strHelperTask->addComponent(objects::STR_HELPER);
|
||||
#if OBSW_ADD_SYRLINKS == 1
|
||||
PeriodicTaskIF* syrlinksCom = factory->createPeriodicTask(
|
||||
"SYRLINKS_COM", 65, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc);
|
||||
result = syrlinksCom->addComponent(objects::SYRLINKS_COM_HANDLER);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("STR_HELPER", objects::STR_HELPER);
|
||||
scheduling::printAddObjectError("SYRLINKS_COM", objects::SYRLINKS_COM_HANDLER);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if OBSW_ADD_STAR_TRACKER == 1
|
||||
// Relatively high priority to make sure STR COM works well.
|
||||
PeriodicTaskIF* strHelperTask =
|
||||
factory->createPeriodicTask("STR_HELPER", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2,
|
||||
missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = strHelperTask->addComponent(objects::STR_COM_IF);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("STR_HELPER", objects::STR_COM_IF);
|
||||
}
|
||||
#endif /* OBSW_ADD_STAR_TRACKER == 1 */
|
||||
|
||||
// TODO: Use regular scheduler for this task
|
||||
#if OBSW_ADD_PLOC_MPSOC == 1
|
||||
PeriodicTaskIF* mpsocHelperTask = factory->createPeriodicTask(
|
||||
"PLOC_MPSOC_HELPER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
||||
PeriodicTaskIF* mpsocHelperTask =
|
||||
factory->createPeriodicTask("PLOC_MPSOC_HELPER", 0, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2,
|
||||
missedDeadlineFunc);
|
||||
result = mpsocHelperTask->addComponent(objects::PLOC_MPSOC_HELPER);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("PLOC_MPSOC_HELPER", objects::PLOC_MPSOC_HELPER);
|
||||
}
|
||||
#endif /* OBSW_ADD_PLOC_MPSOC */
|
||||
|
||||
// TODO: Use regular scheduler for this task
|
||||
#if OBSW_ADD_PLOC_SUPERVISOR == 1
|
||||
PeriodicTaskIF* supvHelperTask = factory->createPeriodicTask(
|
||||
"PLOC_SUPV_HELPER", 10, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc);
|
||||
PeriodicTaskIF* supvHelperTask =
|
||||
factory->createPeriodicTask("PLOC_SUPV_HELPER", 0, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0,
|
||||
missedDeadlineFunc);
|
||||
result = supvHelperTask->addComponent(objects::PLOC_SUPERVISOR_HELPER);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("PLOC_SUPV_HELPER", objects::PLOC_SUPERVISOR_HELPER);
|
||||
@ -334,7 +359,7 @@ void scheduling::initTasks() {
|
||||
#endif /* OBSW_ADD_PLOC_SUPERVISOR */
|
||||
|
||||
PeriodicTaskIF* plTask = factory->createPeriodicTask(
|
||||
"PL_TASK", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc);
|
||||
"PL_TASK", 25, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc, &RR_SCHEDULING);
|
||||
plTask->addComponent(objects::CAM_SWITCHER);
|
||||
scheduling::addMpsocSupvHandlers(plTask);
|
||||
scheduling::scheduleScexDev(plTask);
|
||||
@ -401,6 +426,9 @@ void scheduling::initTasks() {
|
||||
#if OBSW_ADD_ACS_BOARD == 1
|
||||
acsBrdPolling->startTask();
|
||||
#endif
|
||||
#if OBSW_ADD_SYRLINKS == 1
|
||||
syrlinksCom->startTask();
|
||||
#endif
|
||||
#if OBSW_ADD_MGT == 1
|
||||
imtqPolling->startTask();
|
||||
#endif
|
||||
@ -455,8 +483,9 @@ void scheduling::createPstTasks(TaskFactory& factory, TaskDeadlineMissedFunction
|
||||
#else
|
||||
static constexpr float acsPstPeriod = 0.4;
|
||||
#endif
|
||||
FixedTimeslotTaskIF* acsTcsPst = factory.createFixedTimeslotTask(
|
||||
"ACS_TCS_PST", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, acsPstPeriod, missedDeadlineFunc);
|
||||
FixedTimeslotTaskIF* acsTcsPst =
|
||||
factory.createFixedTimeslotTask("ACS_TCS_PST", 85, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2,
|
||||
acsPstPeriod, missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = pst::pstTcsAndAcs(acsTcsPst, cfg);
|
||||
if (result != returnvalue::OK) {
|
||||
if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) {
|
||||
@ -471,7 +500,7 @@ void scheduling::createPstTasks(TaskFactory& factory, TaskDeadlineMissedFunction
|
||||
/* Polling Sequence Table Default */
|
||||
#if OBSW_ADD_SPI_TEST_CODE == 0
|
||||
FixedTimeslotTaskIF* syrlinksPst = factory.createFixedTimeslotTask(
|
||||
"SYRLINKS", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.5, missedDeadlineFunc);
|
||||
"SYRLINKS", 65, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.5, missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = pst::pstSyrlinks(syrlinksPst);
|
||||
if (result != returnvalue::OK) {
|
||||
if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) {
|
||||
@ -485,8 +514,9 @@ void scheduling::createPstTasks(TaskFactory& factory, TaskDeadlineMissedFunction
|
||||
#endif
|
||||
|
||||
#if OBSW_ADD_I2C_TEST_CODE == 0
|
||||
FixedTimeslotTaskIF* i2cPst = factory.createFixedTimeslotTask(
|
||||
"I2C_PST", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.4, missedDeadlineFunc);
|
||||
FixedTimeslotTaskIF* i2cPst =
|
||||
factory.createFixedTimeslotTask("I2C_PS_PST", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.6,
|
||||
missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = pst::pstI2cProcessingSystem(i2cPst);
|
||||
if (result != returnvalue::OK) {
|
||||
if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) {
|
||||
@ -499,8 +529,9 @@ void scheduling::createPstTasks(TaskFactory& factory, TaskDeadlineMissedFunction
|
||||
}
|
||||
#endif
|
||||
|
||||
FixedTimeslotTaskIF* gomSpacePstTask = factory.createFixedTimeslotTask(
|
||||
"GS_PST_TASK", 65, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4, 0.5, missedDeadlineFunc);
|
||||
FixedTimeslotTaskIF* gomSpacePstTask =
|
||||
factory.createFixedTimeslotTask("GS_PST_TASK", 65, PeriodicTaskIF::MINIMUM_STACK_SIZE * 4,
|
||||
0.5, missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = pst::pstGompaceCan(gomSpacePstTask);
|
||||
if (result != returnvalue::OK) {
|
||||
if (result != FixedTimeslotTaskIF::SLOT_LIST_EMPTY) {
|
||||
@ -514,8 +545,9 @@ void scheduling::createPusTasks(TaskFactory& factory, TaskDeadlineMissedFunction
|
||||
std::vector<PeriodicTaskIF*>& taskVec) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
/* PUS Services */
|
||||
PeriodicTaskIF* pusHighPrio = factory.createPeriodicTask(
|
||||
"PUS_HIGH_PRIO", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc);
|
||||
PeriodicTaskIF* pusHighPrio =
|
||||
factory.createPeriodicTask("PUS_HIGH_PRIO", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2,
|
||||
missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = pusHighPrio->addComponent(objects::PUS_SERVICE_1_VERIFICATION);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("PUS_VERIF", objects::PUS_SERVICE_1_VERIFICATION);
|
||||
@ -526,16 +558,17 @@ void scheduling::createPusTasks(TaskFactory& factory, TaskDeadlineMissedFunction
|
||||
}
|
||||
result = pusHighPrio->addComponent(objects::EVENT_MANAGER);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("PUS_MGMT", objects::EVENT_MANAGER);
|
||||
scheduling::printAddObjectError("EVENT_MGMT", objects::EVENT_MANAGER);
|
||||
}
|
||||
result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("PUS_9", objects::PUS_SERVICE_9_TIME_MGMT);
|
||||
scheduling::printAddObjectError("PUS_TIME", objects::PUS_SERVICE_9_TIME_MGMT);
|
||||
}
|
||||
taskVec.push_back(pusHighPrio);
|
||||
|
||||
PeriodicTaskIF* pusMedPrio = factory.createPeriodicTask(
|
||||
"PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc);
|
||||
PeriodicTaskIF* pusMedPrio =
|
||||
factory.createPeriodicTask("PUS_MED_PRIO", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8,
|
||||
missedDeadlineFunc, &RR_SCHEDULING);
|
||||
result = pusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING);
|
||||
if (result != returnvalue::OK) {
|
||||
scheduling::printAddObjectError("PUS_3", objects::PUS_SERVICE_3_HOUSEKEEPING);
|
||||
|
@ -63,7 +63,7 @@ static constexpr dur_millis_t ACS_BOARD_CS_TIMEOUT = 50 * CS_FACTOR;
|
||||
|
||||
} // namespace spi
|
||||
|
||||
namespace uart {
|
||||
namespace serial {
|
||||
|
||||
static constexpr size_t HYPERION_GPS_REPLY_MAX_BUFFER = 1024;
|
||||
static constexpr UartBaudRate SYRLINKS_BAUD = UartBaudRate::RATE_38400;
|
||||
@ -73,6 +73,6 @@ static constexpr UartBaudRate PLOC_MPSOC_BAUD = UartBaudRate::RATE_115200;
|
||||
static constexpr UartBaudRate PLOC_SUPV_BAUD = UartBaudRate::RATE_921600;
|
||||
static constexpr UartBaudRate STAR_TRACKER_BAUD = UartBaudRate::RATE_921600;
|
||||
|
||||
} // namespace uart
|
||||
} // namespace serial
|
||||
|
||||
#endif /* COMMON_CONFIG_DEVCONF_H_ */
|
||||
|
@ -39,6 +39,7 @@ enum : uint8_t {
|
||||
TCS_CONTROLLER = 141,
|
||||
COM_SUBSYSTEM = 142,
|
||||
PERSISTENT_TM_STORE = 143,
|
||||
SYRLINKS_COM = 144,
|
||||
COMMON_SUBSYSTEM_ID_END
|
||||
|
||||
};
|
||||
|
@ -62,7 +62,7 @@ enum commonObjects : uint32_t {
|
||||
RAD_SENSOR = 0x443200A5,
|
||||
PLOC_UPDATER = 0x44330000,
|
||||
PLOC_MEMORY_DUMPER = 0x44330001,
|
||||
STR_HELPER = 0x44330002,
|
||||
STR_COM_IF = 0x44330002,
|
||||
PLOC_MPSOC_HELPER = 0x44330003,
|
||||
AXI_PTME_CONFIG = 0x44330004,
|
||||
PTME_CONFIG = 0x44330005,
|
||||
@ -123,8 +123,7 @@ enum commonObjects : uint32_t {
|
||||
SUS_11_R_LOC_XBYMZB_PT_ZB = 0x44120043,
|
||||
|
||||
SYRLINKS_HANDLER = 0x445300A3,
|
||||
// might be obsolete, was not used in Q7S FM SW
|
||||
// CCSDS_IP_CORE_BRIDGE = 0x73500000,
|
||||
SYRLINKS_COM_HANDLER = 0x445300A4,
|
||||
|
||||
/* 0x49 ('I') for Communication Interfaces */
|
||||
ACS_BOARD_POLLING_TASK = 0x49060004,
|
||||
|
2
fsfw
2
fsfw
@ -1 +1 @@
|
||||
Subproject commit 227524a21da755d125bcb1a5ff67bcbc452f8cf9
|
||||
Subproject commit b814e7198f720cad0fb063f54644d5dbc92c165c
|
@ -156,23 +156,23 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path
|
||||
12409;0x3079;WRITE_SYSCALL_ERROR_PDEC;HIGH;No description;linux/ipcore/PdecHandler.h
|
||||
12410;0x307a;PDEC_RESET_FAILED;HIGH;Failed to pull PDEC reset to low;linux/ipcore/PdecHandler.h
|
||||
12411;0x307b;OPEN_IRQ_FILE_FAILED;HIGH;Failed to open the IRQ uio file;linux/ipcore/PdecHandler.h
|
||||
12500;0x30d4;IMAGE_UPLOAD_FAILED;LOW;Image upload failed;linux/devices/startracker/StrHelper.h
|
||||
12501;0x30d5;IMAGE_DOWNLOAD_FAILED;LOW;Image download failed;linux/devices/startracker/StrHelper.h
|
||||
12502;0x30d6;IMAGE_UPLOAD_SUCCESSFUL;LOW;Uploading image to star tracker was successfulop;linux/devices/startracker/StrHelper.h
|
||||
12503;0x30d7;IMAGE_DOWNLOAD_SUCCESSFUL;LOW;Image download was successful;linux/devices/startracker/StrHelper.h
|
||||
12504;0x30d8;FLASH_WRITE_SUCCESSFUL;LOW;Finished flash write procedure successfully;linux/devices/startracker/StrHelper.h
|
||||
12505;0x30d9;FLASH_READ_SUCCESSFUL;LOW;Finished flash read procedure successfully;linux/devices/startracker/StrHelper.h
|
||||
12506;0x30da;FLASH_READ_FAILED;LOW;Flash read procedure failed;linux/devices/startracker/StrHelper.h
|
||||
12507;0x30db;FIRMWARE_UPDATE_SUCCESSFUL;LOW;Firmware update was successful;linux/devices/startracker/StrHelper.h
|
||||
12508;0x30dc;FIRMWARE_UPDATE_FAILED;LOW;Firmware update failed;linux/devices/startracker/StrHelper.h
|
||||
12509;0x30dd;STR_HELPER_READING_REPLY_FAILED;LOW;Failed to read communication interface reply data P1: Return code of failed communication interface read call P1: Upload/download position for which the read call failed;linux/devices/startracker/StrHelper.h
|
||||
12510;0x30de;STR_HELPER_COM_ERROR;LOW;Unexpected stop of decoding sequence P1: Return code of failed communication interface read call P1: Upload/download position for which the read call failed;linux/devices/startracker/StrHelper.h
|
||||
12511;0x30df;STR_HELPER_NO_REPLY;LOW;Star tracker did not send replies (maybe device is powered off) P1: Position of upload or download packet for which no reply was sent;linux/devices/startracker/StrHelper.h
|
||||
12512;0x30e0;STR_HELPER_DEC_ERROR;LOW;Error during decoding of received reply occurred P1: Return value of decoding function P2: Position of upload/download packet, or address of flash write/read request;linux/devices/startracker/StrHelper.h
|
||||
12513;0x30e1;POSITION_MISMATCH;LOW;Position mismatch P1: The expected position and thus the position for which the image upload/download failed;linux/devices/startracker/StrHelper.h
|
||||
12514;0x30e2;STR_HELPER_FILE_NOT_EXISTS;LOW;Specified file does not exist P1: Internal state of str helper;linux/devices/startracker/StrHelper.h
|
||||
12515;0x30e3;STR_HELPER_SENDING_PACKET_FAILED;LOW;No description;linux/devices/startracker/StrHelper.h
|
||||
12516;0x30e4;STR_HELPER_REQUESTING_MSG_FAILED;LOW;No description;linux/devices/startracker/StrHelper.h
|
||||
12500;0x30d4;IMAGE_UPLOAD_FAILED;LOW;Image upload failed;linux/devices/startracker/StrComHandler.h
|
||||
12501;0x30d5;IMAGE_DOWNLOAD_FAILED;LOW;Image download failed;linux/devices/startracker/StrComHandler.h
|
||||
12502;0x30d6;IMAGE_UPLOAD_SUCCESSFUL;LOW;Uploading image to star tracker was successfulop;linux/devices/startracker/StrComHandler.h
|
||||
12503;0x30d7;IMAGE_DOWNLOAD_SUCCESSFUL;LOW;Image download was successful;linux/devices/startracker/StrComHandler.h
|
||||
12504;0x30d8;FLASH_WRITE_SUCCESSFUL;LOW;Finished flash write procedure successfully;linux/devices/startracker/StrComHandler.h
|
||||
12505;0x30d9;FLASH_READ_SUCCESSFUL;LOW;Finished flash read procedure successfully;linux/devices/startracker/StrComHandler.h
|
||||
12506;0x30da;FLASH_READ_FAILED;LOW;Flash read procedure failed;linux/devices/startracker/StrComHandler.h
|
||||
12507;0x30db;FIRMWARE_UPDATE_SUCCESSFUL;LOW;Firmware update was successful;linux/devices/startracker/StrComHandler.h
|
||||
12508;0x30dc;FIRMWARE_UPDATE_FAILED;LOW;Firmware update failed;linux/devices/startracker/StrComHandler.h
|
||||
12509;0x30dd;STR_HELPER_READING_REPLY_FAILED;LOW;Failed to read communication interface reply data P1: Return code of failed communication interface read call P1: Upload/download position for which the read call failed;linux/devices/startracker/StrComHandler.h
|
||||
12510;0x30de;STR_HELPER_COM_ERROR;LOW;Unexpected stop of decoding sequence P1: Return code of failed communication interface read call P1: Upload/download position for which the read call failed;linux/devices/startracker/StrComHandler.h
|
||||
12511;0x30df;STR_COM_REPLY_TIMEOUT;LOW;Star tracker did not send a valid reply for a certain timeout. P1: Position of upload or download packet for which the packet wa sent. P2: Timeout;linux/devices/startracker/StrComHandler.h
|
||||
12513;0x30e1;STR_HELPER_DEC_ERROR;LOW;Error during decoding of received reply occurred P1: Return value of decoding function P2: Position of upload/download packet, or address of flash write/read request;linux/devices/startracker/StrComHandler.h
|
||||
12514;0x30e2;POSITION_MISMATCH;LOW;Position mismatch P1: The expected position and thus the position for which the image upload/download failed;linux/devices/startracker/StrComHandler.h
|
||||
12515;0x30e3;STR_HELPER_FILE_NOT_EXISTS;LOW;Specified file does not exist P1: Internal state of str helper;linux/devices/startracker/StrComHandler.h
|
||||
12516;0x30e4;STR_HELPER_SENDING_PACKET_FAILED;LOW;No description;linux/devices/startracker/StrComHandler.h
|
||||
12517;0x30e5;STR_HELPER_REQUESTING_MSG_FAILED;LOW;No description;linux/devices/startracker/StrComHandler.h
|
||||
12600;0x3138;MPSOC_FLASH_WRITE_FAILED;LOW;Flash write fails;linux/devices/ploc/PlocMPSoCHelper.h
|
||||
12601;0x3139;MPSOC_FLASH_WRITE_SUCCESSFUL;LOW;Flash write successful;linux/devices/ploc/PlocMPSoCHelper.h
|
||||
12602;0x313a;MPSOC_SENDING_COMMAND_FAILED;LOW;No description;linux/devices/ploc/PlocMPSoCHelper.h
|
||||
@ -240,7 +240,6 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path
|
||||
13630;0x353e;SUPV_UPDATE_PROGRESS;INFO;Will be triggered every 5 percent of the update progress. P1: First byte percent, third and fourth byte Sequence Count, P2: Bytes written;linux/devices/ploc/PlocSupvUartMan.h
|
||||
13631;0x353f;HDLC_FRAME_REMOVAL_ERROR;INFO;No description;linux/devices/ploc/PlocSupvUartMan.h
|
||||
13632;0x3540;HDLC_CRC_ERROR;INFO;No description;linux/devices/ploc/PlocSupvUartMan.h
|
||||
13700;0x3584;FDIR_REACTION_IGNORED;MEDIUM;No description;mission/devices/devicedefinitions/SyrlinksDefinitions.h
|
||||
13701;0x3585;TX_ON;INFO;Transmitter is on now. P1: Submode, P2: Current default datarate.;mission/devices/devicedefinitions/SyrlinksDefinitions.h
|
||||
13702;0x3586;TX_OFF;INFO;Transmitter is off now.;mission/devices/devicedefinitions/SyrlinksDefinitions.h
|
||||
13800;0x35e8;MISSING_PACKET;LOW;No description;mission/devices/devicedefinitions/ScexDefinitions.h
|
||||
|
|
@ -42,7 +42,7 @@
|
||||
0x443200A5;RAD_SENSOR
|
||||
0x44330000;PLOC_UPDATER
|
||||
0x44330001;PLOC_MEMORY_DUMPER
|
||||
0x44330002;STR_HELPER
|
||||
0x44330002;STR_COM_IF
|
||||
0x44330003;PLOC_MPSOC_HELPER
|
||||
0x44330004;AXI_PTME_CONFIG
|
||||
0x44330005;PTME_CONFIG
|
||||
@ -78,6 +78,7 @@
|
||||
0x44420030;RTD_14_IC17_TCS_BOARD
|
||||
0x44420031;RTD_15_IC18_IMTQ
|
||||
0x445300A3;SYRLINKS_HANDLER
|
||||
0x445300A4;SYRLINKS_COM_HANDLER
|
||||
0x49000001;ARDUINO_COM_IF
|
||||
0x49000002;DUMMY_COM_IF
|
||||
0x49010006;SCEX_UART_READER
|
||||
@ -163,7 +164,6 @@
|
||||
0x73040002;HK_STORE_AND_TM_TASK
|
||||
0x73040003;CFDP_STORE_AND_TM_TASK
|
||||
0x73040004;DOWNLINK_RAM_STORE
|
||||
0x73500000;CCSDS_IP_CORE_BRIDGE
|
||||
0x90000003;THERMAL_TEMP_INSERTER
|
||||
0xCAFECAFE;DUMMY_INTERFACE
|
||||
0xFFFFFFFF;NO_OBJECT
|
||||
|
|
@ -190,8 +190,8 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
||||
0x2207;TMF_AllDeleted;No description;7;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
|
||||
0x2208;TMF_InvalidData;No description;8;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
|
||||
0x2209;TMF_NotReady;No description;9;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
|
||||
0x2401;MT_NoPacketFound;No description;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h
|
||||
0x2402;MT_PossiblePacketLoss;No description;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h
|
||||
0x2401;MT_TooDetailedRequest;No description;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
|
||||
0x2402;MT_TooGeneralRequest;No description;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
|
||||
0x2403;MT_NoMatch;No description;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
|
||||
0x2404;MT_Full;No description;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
|
||||
0x2405;MT_NewNodeCreated;No description;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
|
||||
@ -321,6 +321,7 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
||||
0x3404;DC_InvalidCookieType;No description;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
|
||||
0x3405;DC_NotActive;No description;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
|
||||
0x3406;DC_TooMuchData;No description;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
|
||||
0x3407;DC_Busy;No description;7;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
|
||||
0x3601;CFDP_InvalidTlvType;No description;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h
|
||||
0x3602;CFDP_InvalidDirectiveField;No description;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h
|
||||
0x3603;CFDP_InvalidPduDatafieldLen;No description;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h
|
||||
@ -370,8 +371,8 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
||||
0x3e03;HKM_PeriodicHelperInvalid;No description;3;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
|
||||
0x3e04;HKM_PoolobjectNotFound;No description;4;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
|
||||
0x3e05;HKM_DatasetNotFound;No description;5;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
|
||||
0x3f01;DLEE_StreamTooShort;No description;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h
|
||||
0x3f02;DLEE_DecodingError;No description;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h
|
||||
0x3f01;DLEE_NoPacketFound;No description;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h
|
||||
0x3f02;DLEE_PossiblePacketLoss;No description;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h
|
||||
0x4201;PUS11_InvalidTypeTimeWindow;No description;1;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
|
||||
0x4202;PUS11_InvalidTimeWindow;No description;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
|
||||
0x4203;PUS11_TimeshiftingNotPossible;No description;3;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
|
||||
@ -401,9 +402,9 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
||||
0x4403;UXOS_CommandError;Command execution failed;3;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
|
||||
0x4404;UXOS_NoCommandLoadedOrPending;;4;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
|
||||
0x4406;UXOS_PcloseCallError;No description;6;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
|
||||
0x4500;HSPI_HalTimeoutRetval;No description;0;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h
|
||||
0x4501;HSPI_HalBusyRetval;No description;1;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h
|
||||
0x4502;HSPI_HalErrorRetval;No description;2;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h
|
||||
0x4500;HSPI_OpeningFileFailed;No description;0;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
|
||||
0x4501;HSPI_FullDuplexTransferFailed;No description;1;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
|
||||
0x4502;HSPI_HalfDuplexTransferFailed;No description;2;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
|
||||
0x4601;HURT_UartReadFailure;No description;1;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
|
||||
0x4602;HURT_UartReadSizeMissmatch;No description;2;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
|
||||
0x4603;HURT_UartRxBufferTooSmall;No description;3;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
|
||||
@ -456,19 +457,14 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
||||
0x5d03;GOMS_InvalidParamSize;No description;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
|
||||
0x5d04;GOMS_InvalidPayloadSize;No description;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
|
||||
0x5d05;GOMS_UnknownReplyId;No description;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
|
||||
0x5da0;GOMS_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
|
||||
0x5da1;GOMS_InvalidRampTime;Action Message with invalid ramp time was received.;161;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
|
||||
0x5da2;GOMS_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
|
||||
0x5da3;GOMS_ExecutionFailed;Command execution failed;163;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
|
||||
0x5da4;GOMS_CrcError;Reaction wheel reply has invalid crc;164;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
|
||||
0x5da5;GOMS_ValueNotRead;No description;165;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
|
||||
0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h
|
||||
0x63a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NvmParameterBase.h
|
||||
0x66a0;SADPL_CommandNotSupported;No description;160;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
|
||||
0x66a1;SADPL_DeploymentAlreadyExecuting;No description;161;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
|
||||
0x66a2;SADPL_MainSwitchTimeoutFailure;No description;162;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
|
||||
0x66a3;SADPL_SwitchingDeplSa1Failed;No description;163;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
|
||||
0x66a4;SADPL_SwitchingDeplSa2Failed;No description;164;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
|
||||
0x66a0;SADPL_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;SA_DEPL_HANDLER;mission/devices/RwHandler.h
|
||||
0x66a1;SADPL_InvalidRampTime;Action Message with invalid ramp time was received.;161;SA_DEPL_HANDLER;mission/devices/RwHandler.h
|
||||
0x66a2;SADPL_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;SA_DEPL_HANDLER;mission/devices/RwHandler.h
|
||||
0x66a3;SADPL_ExecutionFailed;Command execution failed;163;SA_DEPL_HANDLER;mission/devices/RwHandler.h
|
||||
0x66a4;SADPL_CrcError;Reaction wheel reply has invalid crc;164;SA_DEPL_HANDLER;mission/devices/RwHandler.h
|
||||
0x66a5;SADPL_ValueNotRead;No description;165;SA_DEPL_HANDLER;mission/devices/RwHandler.h
|
||||
0x6900;ACSCTRL_FileDeletionFailed;No description;0;ACS_CTRL;mission/controller/AcsController.h
|
||||
0x6a02;ACSMEKF_MekfUninitialized;No description;2;ACS_MEKF;mission/controller/acs/MultiplicativeKalmanFilter.h
|
||||
0x6a03;ACSMEKF_MekfNoGyrData;No description;3;ACS_MEKF;mission/controller/acs/MultiplicativeKalmanFilter.h
|
||||
|
|
@ -59,3 +59,4 @@
|
||||
141;TCS_CONTROLLER
|
||||
142;COM_SUBSYSTEM
|
||||
143;PERSISTENT_TM_STORE
|
||||
144;SYRLINKS_COM
|
||||
|
|
@ -156,23 +156,23 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path
|
||||
12409;0x3079;WRITE_SYSCALL_ERROR_PDEC;HIGH;No description;linux/ipcore/PdecHandler.h
|
||||
12410;0x307a;PDEC_RESET_FAILED;HIGH;Failed to pull PDEC reset to low;linux/ipcore/PdecHandler.h
|
||||
12411;0x307b;OPEN_IRQ_FILE_FAILED;HIGH;Failed to open the IRQ uio file;linux/ipcore/PdecHandler.h
|
||||
12500;0x30d4;IMAGE_UPLOAD_FAILED;LOW;Image upload failed;linux/devices/startracker/StrHelper.h
|
||||
12501;0x30d5;IMAGE_DOWNLOAD_FAILED;LOW;Image download failed;linux/devices/startracker/StrHelper.h
|
||||
12502;0x30d6;IMAGE_UPLOAD_SUCCESSFUL;LOW;Uploading image to star tracker was successfulop;linux/devices/startracker/StrHelper.h
|
||||
12503;0x30d7;IMAGE_DOWNLOAD_SUCCESSFUL;LOW;Image download was successful;linux/devices/startracker/StrHelper.h
|
||||
12504;0x30d8;FLASH_WRITE_SUCCESSFUL;LOW;Finished flash write procedure successfully;linux/devices/startracker/StrHelper.h
|
||||
12505;0x30d9;FLASH_READ_SUCCESSFUL;LOW;Finished flash read procedure successfully;linux/devices/startracker/StrHelper.h
|
||||
12506;0x30da;FLASH_READ_FAILED;LOW;Flash read procedure failed;linux/devices/startracker/StrHelper.h
|
||||
12507;0x30db;FIRMWARE_UPDATE_SUCCESSFUL;LOW;Firmware update was successful;linux/devices/startracker/StrHelper.h
|
||||
12508;0x30dc;FIRMWARE_UPDATE_FAILED;LOW;Firmware update failed;linux/devices/startracker/StrHelper.h
|
||||
12509;0x30dd;STR_HELPER_READING_REPLY_FAILED;LOW;Failed to read communication interface reply data P1: Return code of failed communication interface read call P1: Upload/download position for which the read call failed;linux/devices/startracker/StrHelper.h
|
||||
12510;0x30de;STR_HELPER_COM_ERROR;LOW;Unexpected stop of decoding sequence P1: Return code of failed communication interface read call P1: Upload/download position for which the read call failed;linux/devices/startracker/StrHelper.h
|
||||
12511;0x30df;STR_HELPER_NO_REPLY;LOW;Star tracker did not send replies (maybe device is powered off) P1: Position of upload or download packet for which no reply was sent;linux/devices/startracker/StrHelper.h
|
||||
12512;0x30e0;STR_HELPER_DEC_ERROR;LOW;Error during decoding of received reply occurred P1: Return value of decoding function P2: Position of upload/download packet, or address of flash write/read request;linux/devices/startracker/StrHelper.h
|
||||
12513;0x30e1;POSITION_MISMATCH;LOW;Position mismatch P1: The expected position and thus the position for which the image upload/download failed;linux/devices/startracker/StrHelper.h
|
||||
12514;0x30e2;STR_HELPER_FILE_NOT_EXISTS;LOW;Specified file does not exist P1: Internal state of str helper;linux/devices/startracker/StrHelper.h
|
||||
12515;0x30e3;STR_HELPER_SENDING_PACKET_FAILED;LOW;No description;linux/devices/startracker/StrHelper.h
|
||||
12516;0x30e4;STR_HELPER_REQUESTING_MSG_FAILED;LOW;No description;linux/devices/startracker/StrHelper.h
|
||||
12500;0x30d4;IMAGE_UPLOAD_FAILED;LOW;Image upload failed;linux/devices/startracker/StrComHandler.h
|
||||
12501;0x30d5;IMAGE_DOWNLOAD_FAILED;LOW;Image download failed;linux/devices/startracker/StrComHandler.h
|
||||
12502;0x30d6;IMAGE_UPLOAD_SUCCESSFUL;LOW;Uploading image to star tracker was successfulop;linux/devices/startracker/StrComHandler.h
|
||||
12503;0x30d7;IMAGE_DOWNLOAD_SUCCESSFUL;LOW;Image download was successful;linux/devices/startracker/StrComHandler.h
|
||||
12504;0x30d8;FLASH_WRITE_SUCCESSFUL;LOW;Finished flash write procedure successfully;linux/devices/startracker/StrComHandler.h
|
||||
12505;0x30d9;FLASH_READ_SUCCESSFUL;LOW;Finished flash read procedure successfully;linux/devices/startracker/StrComHandler.h
|
||||
12506;0x30da;FLASH_READ_FAILED;LOW;Flash read procedure failed;linux/devices/startracker/StrComHandler.h
|
||||
12507;0x30db;FIRMWARE_UPDATE_SUCCESSFUL;LOW;Firmware update was successful;linux/devices/startracker/StrComHandler.h
|
||||
12508;0x30dc;FIRMWARE_UPDATE_FAILED;LOW;Firmware update failed;linux/devices/startracker/StrComHandler.h
|
||||
12509;0x30dd;STR_HELPER_READING_REPLY_FAILED;LOW;Failed to read communication interface reply data P1: Return code of failed communication interface read call P1: Upload/download position for which the read call failed;linux/devices/startracker/StrComHandler.h
|
||||
12510;0x30de;STR_HELPER_COM_ERROR;LOW;Unexpected stop of decoding sequence P1: Return code of failed communication interface read call P1: Upload/download position for which the read call failed;linux/devices/startracker/StrComHandler.h
|
||||
12511;0x30df;STR_COM_REPLY_TIMEOUT;LOW;Star tracker did not send a valid reply for a certain timeout. P1: Position of upload or download packet for which the packet wa sent. P2: Timeout;linux/devices/startracker/StrComHandler.h
|
||||
12513;0x30e1;STR_HELPER_DEC_ERROR;LOW;Error during decoding of received reply occurred P1: Return value of decoding function P2: Position of upload/download packet, or address of flash write/read request;linux/devices/startracker/StrComHandler.h
|
||||
12514;0x30e2;POSITION_MISMATCH;LOW;Position mismatch P1: The expected position and thus the position for which the image upload/download failed;linux/devices/startracker/StrComHandler.h
|
||||
12515;0x30e3;STR_HELPER_FILE_NOT_EXISTS;LOW;Specified file does not exist P1: Internal state of str helper;linux/devices/startracker/StrComHandler.h
|
||||
12516;0x30e4;STR_HELPER_SENDING_PACKET_FAILED;LOW;No description;linux/devices/startracker/StrComHandler.h
|
||||
12517;0x30e5;STR_HELPER_REQUESTING_MSG_FAILED;LOW;No description;linux/devices/startracker/StrComHandler.h
|
||||
12600;0x3138;MPSOC_FLASH_WRITE_FAILED;LOW;Flash write fails;linux/devices/ploc/PlocMPSoCHelper.h
|
||||
12601;0x3139;MPSOC_FLASH_WRITE_SUCCESSFUL;LOW;Flash write successful;linux/devices/ploc/PlocMPSoCHelper.h
|
||||
12602;0x313a;MPSOC_SENDING_COMMAND_FAILED;LOW;No description;linux/devices/ploc/PlocMPSoCHelper.h
|
||||
@ -240,7 +240,6 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path
|
||||
13630;0x353e;SUPV_UPDATE_PROGRESS;INFO;Will be triggered every 5 percent of the update progress. P1: First byte percent, third and fourth byte Sequence Count, P2: Bytes written;linux/devices/ploc/PlocSupvUartMan.h
|
||||
13631;0x353f;HDLC_FRAME_REMOVAL_ERROR;INFO;No description;linux/devices/ploc/PlocSupvUartMan.h
|
||||
13632;0x3540;HDLC_CRC_ERROR;INFO;No description;linux/devices/ploc/PlocSupvUartMan.h
|
||||
13700;0x3584;FDIR_REACTION_IGNORED;MEDIUM;No description;mission/devices/devicedefinitions/SyrlinksDefinitions.h
|
||||
13701;0x3585;TX_ON;INFO;Transmitter is on now. P1: Submode, P2: Current default datarate.;mission/devices/devicedefinitions/SyrlinksDefinitions.h
|
||||
13702;0x3586;TX_OFF;INFO;Transmitter is off now.;mission/devices/devicedefinitions/SyrlinksDefinitions.h
|
||||
13800;0x35e8;MISSING_PACKET;LOW;No description;mission/devices/devicedefinitions/ScexDefinitions.h
|
||||
|
|
@ -41,7 +41,7 @@
|
||||
0x443200A5;RAD_SENSOR
|
||||
0x44330000;PLOC_UPDATER
|
||||
0x44330001;PLOC_MEMORY_DUMPER
|
||||
0x44330002;STR_HELPER
|
||||
0x44330002;STR_COM_IF
|
||||
0x44330003;PLOC_MPSOC_HELPER
|
||||
0x44330004;AXI_PTME_CONFIG
|
||||
0x44330005;PTME_CONFIG
|
||||
@ -77,6 +77,7 @@
|
||||
0x44420030;RTD_14_IC17_TCS_BOARD
|
||||
0x44420031;RTD_15_IC18_IMTQ
|
||||
0x445300A3;SYRLINKS_HANDLER
|
||||
0x445300A4;SYRLINKS_COM_HANDLER
|
||||
0x49000000;ARDUINO_COM_IF
|
||||
0x49010005;GPIO_IF
|
||||
0x49010006;SCEX_UART_READER
|
||||
@ -168,6 +169,5 @@
|
||||
0x73040002;HK_STORE_AND_TM_TASK
|
||||
0x73040003;CFDP_STORE_AND_TM_TASK
|
||||
0x73040004;DOWNLINK_RAM_STORE
|
||||
0x73500000;CCSDS_IP_CORE_BRIDGE
|
||||
0x90000003;THERMAL_TEMP_INSERTER
|
||||
0xFFFFFFFF;NO_OBJECT
|
||||
|
|
@ -190,8 +190,8 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
||||
0x2207;TMF_AllDeleted;No description;7;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
|
||||
0x2208;TMF_InvalidData;No description;8;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
|
||||
0x2209;TMF_NotReady;No description;9;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
|
||||
0x2401;MT_NoPacketFound;No description;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h
|
||||
0x2402;MT_PossiblePacketLoss;No description;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h
|
||||
0x2401;MT_TooDetailedRequest;No description;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
|
||||
0x2402;MT_TooGeneralRequest;No description;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
|
||||
0x2403;MT_NoMatch;No description;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
|
||||
0x2404;MT_Full;No description;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
|
||||
0x2405;MT_NewNodeCreated;No description;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
|
||||
@ -321,6 +321,7 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
||||
0x3404;DC_InvalidCookieType;No description;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
|
||||
0x3405;DC_NotActive;No description;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
|
||||
0x3406;DC_TooMuchData;No description;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
|
||||
0x3407;DC_Busy;No description;7;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
|
||||
0x3601;CFDP_InvalidTlvType;No description;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h
|
||||
0x3602;CFDP_InvalidDirectiveField;No description;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h
|
||||
0x3603;CFDP_InvalidPduDatafieldLen;No description;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h
|
||||
@ -370,8 +371,8 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
||||
0x3e03;HKM_PeriodicHelperInvalid;No description;3;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
|
||||
0x3e04;HKM_PoolobjectNotFound;No description;4;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
|
||||
0x3e05;HKM_DatasetNotFound;No description;5;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
|
||||
0x3f01;DLEE_StreamTooShort;No description;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h
|
||||
0x3f02;DLEE_DecodingError;No description;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h
|
||||
0x3f01;DLEE_NoPacketFound;No description;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h
|
||||
0x3f02;DLEE_PossiblePacketLoss;No description;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h
|
||||
0x4201;PUS11_InvalidTypeTimeWindow;No description;1;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
|
||||
0x4202;PUS11_InvalidTimeWindow;No description;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
|
||||
0x4203;PUS11_TimeshiftingNotPossible;No description;3;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
|
||||
@ -401,9 +402,9 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
||||
0x4403;UXOS_CommandError;Command execution failed;3;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
|
||||
0x4404;UXOS_NoCommandLoadedOrPending;;4;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
|
||||
0x4406;UXOS_PcloseCallError;No description;6;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
|
||||
0x4500;HSPI_HalTimeoutRetval;No description;0;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h
|
||||
0x4501;HSPI_HalBusyRetval;No description;1;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h
|
||||
0x4502;HSPI_HalErrorRetval;No description;2;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h
|
||||
0x4500;HSPI_OpeningFileFailed;No description;0;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
|
||||
0x4501;HSPI_FullDuplexTransferFailed;No description;1;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
|
||||
0x4502;HSPI_HalfDuplexTransferFailed;No description;2;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
|
||||
0x4601;HURT_UartReadFailure;No description;1;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
|
||||
0x4602;HURT_UartReadSizeMissmatch;No description;2;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
|
||||
0x4603;HURT_UartRxBufferTooSmall;No description;3;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
|
||||
@ -473,8 +474,6 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
||||
0x53b6;STRH_StartrackerAlreadyBooted;Star tracker is already in firmware mode;182;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
|
||||
0x53b7;STRH_StartrackerNotRunningFirmware;Star tracker must be in firmware mode to run this command;183;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
|
||||
0x53b8;STRH_StartrackerNotRunningBootloader;Star tracker must be in bootloader mode to run this command;184;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
|
||||
0x5400;DWLPWRON_NoReplyAvailable;No description;0;DWLPWRON_CMD;linux/devices/ImtqPollingTask.h
|
||||
0x5402;DWLPWRON_InvalidCrc;No description;2;DWLPWRON_CMD;linux/devices/ScexHelper.h
|
||||
0x54e0;DWLPWRON_InvalidMode;Received command has invalid JESD mode (valid modes are 0 - 5);224;DWLPWRON_CMD;linux/devices/devicedefinitions/PlocMPSoCDefinitions.h
|
||||
0x54e1;DWLPWRON_InvalidLaneRate;Received command has invalid lane rate (valid lane rate are 0 - 9);225;DWLPWRON_CMD;linux/devices/devicedefinitions/PlocMPSoCDefinitions.h
|
||||
0x5700;PLSPVhLP_RequestDone;No description;0;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h
|
||||
@ -491,27 +490,24 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
||||
0x58a1;SUSS_ErrorLockMutex;No description;161;SUS_HANDLER;mission/devices/LegacySusHandler.h
|
||||
0x59a0;IPCI_PapbBusy;No description;160;CCSDS_IP_CORE_BRIDGE;linux/ipcore/PapbVcInterface.h
|
||||
0x5aa0;PTME_UnknownVcId;No description;160;PTME;linux/ipcore/Ptme.h
|
||||
0x5ca0;STRHLP_SdNotMounted;SD card specified in path string not mounted;160;STR_HELPER;linux/devices/startracker/StrHelper.h
|
||||
0x5ca1;STRHLP_FileNotExists;Specified file does not exist on filesystem;161;STR_HELPER;linux/devices/startracker/StrHelper.h
|
||||
0x5ca2;STRHLP_PathNotExists;Specified path does not exist;162;STR_HELPER;linux/devices/startracker/StrHelper.h
|
||||
0x5ca3;STRHLP_FileCreationFailed;Failed to create download image or read flash file;163;STR_HELPER;linux/devices/startracker/StrHelper.h
|
||||
0x5ca4;STRHLP_RegionMismatch;Region in flash write/read reply does not match expected region;164;STR_HELPER;linux/devices/startracker/StrHelper.h
|
||||
0x5ca5;STRHLP_AddressMismatch;Address in flash write/read reply does not match expected address;165;STR_HELPER;linux/devices/startracker/StrHelper.h
|
||||
0x5ca6;STRHLP_LengthMismatch;Length in flash write/read reply does not match expected length;166;STR_HELPER;linux/devices/startracker/StrHelper.h
|
||||
0x5ca7;STRHLP_StatusError;Status field in reply signals error;167;STR_HELPER;linux/devices/startracker/StrHelper.h
|
||||
0x5ca8;STRHLP_InvalidTypeId;Reply has invalid type ID (should be of action reply type);168;STR_HELPER;linux/devices/startracker/StrHelper.h
|
||||
0x5c00;STRHLP_NoReplyAvailable;No description;0;STR_HELPER;linux/devices/ImtqPollingTask.h
|
||||
0x5c01;STRHLP_NoPacketFound;No description;1;STR_HELPER;linux/devices/SyrlinksComHandler.h
|
||||
0x5c02;STRHLP_InvalidCrc;No description;2;STR_HELPER;linux/devices/ScexHelper.h
|
||||
0x5c03;STRHLP_PathNotExists;Specified path does not exist;3;STR_HELPER;linux/devices/startracker/StrComHandler.h
|
||||
0x5c04;STRHLP_FileCreationFailed;Failed to create download image or read flash file;4;STR_HELPER;linux/devices/startracker/StrComHandler.h
|
||||
0x5c05;STRHLP_RegionMismatch;Region in flash write/read reply does not match expected region;5;STR_HELPER;linux/devices/startracker/StrComHandler.h
|
||||
0x5c06;STRHLP_AddressMismatch;Address in flash write/read reply does not match expected address;6;STR_HELPER;linux/devices/startracker/StrComHandler.h
|
||||
0x5c07;STRHLP_LengthMismatch;Length in flash write/read reply does not match expected length;7;STR_HELPER;linux/devices/startracker/StrComHandler.h
|
||||
0x5c08;STRHLP_StatusError;Status field in reply signals error;8;STR_HELPER;linux/devices/startracker/StrComHandler.h
|
||||
0x5c09;STRHLP_InvalidTypeId;Reply has invalid type ID (should be of action reply type);9;STR_HELPER;linux/devices/startracker/StrComHandler.h
|
||||
0x5c0a;STRHLP_ReceptionTimeout;No description;10;STR_HELPER;linux/devices/startracker/StrComHandler.h
|
||||
0x5c0b;STRHLP_DecodingError;No description;11;STR_HELPER;linux/devices/startracker/StrComHandler.h
|
||||
0x5d00;GOMS_PacketTooLong;No description;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
|
||||
0x5d01;GOMS_InvalidTableId;No description;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
|
||||
0x5d02;GOMS_InvalidAddress;No description;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
|
||||
0x5d03;GOMS_InvalidParamSize;No description;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
|
||||
0x5d04;GOMS_InvalidPayloadSize;No description;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
|
||||
0x5d05;GOMS_UnknownReplyId;No description;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
|
||||
0x5da0;GOMS_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
|
||||
0x5da1;GOMS_InvalidRampTime;Action Message with invalid ramp time was received.;161;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
|
||||
0x5da2;GOMS_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
|
||||
0x5da3;GOMS_ExecutionFailed;Command execution failed;163;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
|
||||
0x5da4;GOMS_CrcError;Reaction wheel reply has invalid crc;164;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
|
||||
0x5da5;GOMS_ValueNotRead;No description;165;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
|
||||
0x5ea0;PLMEMDUMP_MramAddressTooHigh;The capacity of the MRAM amounts to 512 kB. Thus the maximum address must not be higher than 0x7d000.;160;PLOC_MEMORY_DUMPER;linux/devices/ploc/PlocMemoryDumper.h
|
||||
0x5ea1;PLMEMDUMP_MramInvalidAddressCombination;The specified end address is lower than the start address;161;PLOC_MEMORY_DUMPER;linux/devices/ploc/PlocMemoryDumper.h
|
||||
0x5fa0;PDEC_AbandonedCltuRetval;No description;160;PDEC_HANDLER;linux/ipcore/PdecHandler.h
|
||||
@ -541,11 +537,12 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
|
||||
0x64a0;FSHLP_SdNotMounted;SD card specified with path string not mounted;160;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h
|
||||
0x64a1;FSHLP_FileNotExists;Specified file does not exist on filesystem;161;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h
|
||||
0x65a0;PLMPHLP_FileClosedAccidentally;File accidentally close;160;PLOC_MPSOC_HELPER;linux/devices/ploc/PlocMPSoCHelper.h
|
||||
0x66a0;SADPL_CommandNotSupported;No description;160;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
|
||||
0x66a1;SADPL_DeploymentAlreadyExecuting;No description;161;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
|
||||
0x66a2;SADPL_MainSwitchTimeoutFailure;No description;162;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
|
||||
0x66a3;SADPL_SwitchingDeplSa1Failed;No description;163;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
|
||||
0x66a4;SADPL_SwitchingDeplSa2Failed;No description;164;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
|
||||
0x66a0;SADPL_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;SA_DEPL_HANDLER;mission/devices/RwHandler.h
|
||||
0x66a1;SADPL_InvalidRampTime;Action Message with invalid ramp time was received.;161;SA_DEPL_HANDLER;mission/devices/RwHandler.h
|
||||
0x66a2;SADPL_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;SA_DEPL_HANDLER;mission/devices/RwHandler.h
|
||||
0x66a3;SADPL_ExecutionFailed;Command execution failed;163;SA_DEPL_HANDLER;mission/devices/RwHandler.h
|
||||
0x66a4;SADPL_CrcError;Reaction wheel reply has invalid crc;164;SA_DEPL_HANDLER;mission/devices/RwHandler.h
|
||||
0x66a5;SADPL_ValueNotRead;No description;165;SA_DEPL_HANDLER;mission/devices/RwHandler.h
|
||||
0x67a0;MPSOCRTVIF_CrcFailure;Space Packet received from PLOC has invalid CRC;160;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
|
||||
0x67a1;MPSOCRTVIF_ReceivedAckFailure;Received ACK failure reply from PLOC;161;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
|
||||
0x67a2;MPSOCRTVIF_ReceivedExeFailure;Received execution failure reply from PLOC;162;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
|
||||
|
|
@ -59,3 +59,4 @@
|
||||
141;TCS_CONTROLLER
|
||||
142;COM_SUBSYSTEM
|
||||
143;PERSISTENT_TM_STORE
|
||||
144;SYRLINKS_COM
|
||||
|
|
@ -1,7 +1,7 @@
|
||||
/**
|
||||
* @brief Auto-generated event translation file. Contains 280 translations.
|
||||
* @brief Auto-generated event translation file. Contains 279 translations.
|
||||
* @details
|
||||
* Generated on: 2023-03-23 10:28:33
|
||||
* Generated on: 2023-03-24 14:59:06
|
||||
*/
|
||||
#include "translateEvents.h"
|
||||
|
||||
@ -173,7 +173,7 @@ const char *FIRMWARE_UPDATE_SUCCESSFUL_STRING = "FIRMWARE_UPDATE_SUCCESSFUL";
|
||||
const char *FIRMWARE_UPDATE_FAILED_STRING = "FIRMWARE_UPDATE_FAILED";
|
||||
const char *STR_HELPER_READING_REPLY_FAILED_STRING = "STR_HELPER_READING_REPLY_FAILED";
|
||||
const char *STR_HELPER_COM_ERROR_STRING = "STR_HELPER_COM_ERROR";
|
||||
const char *STR_HELPER_NO_REPLY_STRING = "STR_HELPER_NO_REPLY";
|
||||
const char *STR_COM_REPLY_TIMEOUT_STRING = "STR_COM_REPLY_TIMEOUT";
|
||||
const char *STR_HELPER_DEC_ERROR_STRING = "STR_HELPER_DEC_ERROR";
|
||||
const char *POSITION_MISMATCH_STRING = "POSITION_MISMATCH";
|
||||
const char *STR_HELPER_FILE_NOT_EXISTS_STRING = "STR_HELPER_FILE_NOT_EXISTS";
|
||||
@ -620,16 +620,16 @@ const char *translateEvents(Event event) {
|
||||
case (12510):
|
||||
return STR_HELPER_COM_ERROR_STRING;
|
||||
case (12511):
|
||||
return STR_HELPER_NO_REPLY_STRING;
|
||||
case (12512):
|
||||
return STR_HELPER_DEC_ERROR_STRING;
|
||||
return STR_COM_REPLY_TIMEOUT_STRING;
|
||||
case (12513):
|
||||
return POSITION_MISMATCH_STRING;
|
||||
return STR_HELPER_DEC_ERROR_STRING;
|
||||
case (12514):
|
||||
return STR_HELPER_FILE_NOT_EXISTS_STRING;
|
||||
return POSITION_MISMATCH_STRING;
|
||||
case (12515):
|
||||
return STR_HELPER_SENDING_PACKET_FAILED_STRING;
|
||||
return STR_HELPER_FILE_NOT_EXISTS_STRING;
|
||||
case (12516):
|
||||
return STR_HELPER_SENDING_PACKET_FAILED_STRING;
|
||||
case (12517):
|
||||
return STR_HELPER_REQUESTING_MSG_FAILED_STRING;
|
||||
case (12600):
|
||||
return MPSOC_FLASH_WRITE_FAILED_STRING;
|
||||
|
@ -2,7 +2,7 @@
|
||||
* @brief Auto-generated object translation file.
|
||||
* @details
|
||||
* Contains 173 translations.
|
||||
* Generated on: 2023-03-21 23:59:36
|
||||
* Generated on: 2023-03-24 14:59:06
|
||||
*/
|
||||
#include "translateObjects.h"
|
||||
|
||||
@ -49,7 +49,7 @@ const char *PLPCDU_HANDLER_STRING = "PLPCDU_HANDLER";
|
||||
const char *RAD_SENSOR_STRING = "RAD_SENSOR";
|
||||
const char *PLOC_UPDATER_STRING = "PLOC_UPDATER";
|
||||
const char *PLOC_MEMORY_DUMPER_STRING = "PLOC_MEMORY_DUMPER";
|
||||
const char *STR_HELPER_STRING = "STR_HELPER";
|
||||
const char *STR_COM_IF_STRING = "STR_COM_IF";
|
||||
const char *PLOC_MPSOC_HELPER_STRING = "PLOC_MPSOC_HELPER";
|
||||
const char *AXI_PTME_CONFIG_STRING = "AXI_PTME_CONFIG";
|
||||
const char *PTME_CONFIG_STRING = "PTME_CONFIG";
|
||||
@ -85,6 +85,7 @@ const char *RTD_13_IC16_PLPCDU_HEATSPREADER_STRING = "RTD_13_IC16_PLPCDU_HEATSPR
|
||||
const char *RTD_14_IC17_TCS_BOARD_STRING = "RTD_14_IC17_TCS_BOARD";
|
||||
const char *RTD_15_IC18_IMTQ_STRING = "RTD_15_IC18_IMTQ";
|
||||
const char *SYRLINKS_HANDLER_STRING = "SYRLINKS_HANDLER";
|
||||
const char *SYRLINKS_COM_HANDLER_STRING = "SYRLINKS_COM_HANDLER";
|
||||
const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF";
|
||||
const char *GPIO_IF_STRING = "GPIO_IF";
|
||||
const char *SCEX_UART_READER_STRING = "SCEX_UART_READER";
|
||||
@ -176,7 +177,6 @@ const char *LOG_STORE_AND_TM_TASK_STRING = "LOG_STORE_AND_TM_TASK";
|
||||
const char *HK_STORE_AND_TM_TASK_STRING = "HK_STORE_AND_TM_TASK";
|
||||
const char *CFDP_STORE_AND_TM_TASK_STRING = "CFDP_STORE_AND_TM_TASK";
|
||||
const char *DOWNLINK_RAM_STORE_STRING = "DOWNLINK_RAM_STORE";
|
||||
const char *CCSDS_IP_CORE_BRIDGE_STRING = "CCSDS_IP_CORE_BRIDGE";
|
||||
const char *THERMAL_TEMP_INSERTER_STRING = "THERMAL_TEMP_INSERTER";
|
||||
const char *NO_OBJECT_STRING = "NO_OBJECT";
|
||||
|
||||
@ -269,7 +269,7 @@ const char *translateObject(object_id_t object) {
|
||||
case 0x44330001:
|
||||
return PLOC_MEMORY_DUMPER_STRING;
|
||||
case 0x44330002:
|
||||
return STR_HELPER_STRING;
|
||||
return STR_COM_IF_STRING;
|
||||
case 0x44330003:
|
||||
return PLOC_MPSOC_HELPER_STRING;
|
||||
case 0x44330004:
|
||||
@ -340,6 +340,8 @@ const char *translateObject(object_id_t object) {
|
||||
return RTD_15_IC18_IMTQ_STRING;
|
||||
case 0x445300A3:
|
||||
return SYRLINKS_HANDLER_STRING;
|
||||
case 0x445300A4:
|
||||
return SYRLINKS_COM_HANDLER_STRING;
|
||||
case 0x49000000:
|
||||
return ARDUINO_COM_IF_STRING;
|
||||
case 0x49010005:
|
||||
@ -522,8 +524,6 @@ const char *translateObject(object_id_t object) {
|
||||
return CFDP_STORE_AND_TM_TASK_STRING;
|
||||
case 0x73040004:
|
||||
return DOWNLINK_RAM_STORE_STRING;
|
||||
case 0x73500000:
|
||||
return CCSDS_IP_CORE_BRIDGE_STRING;
|
||||
case 0x90000003:
|
||||
return THERMAL_TEMP_INSERTER_STRING;
|
||||
case 0xFFFFFFFF:
|
||||
|
@ -314,7 +314,7 @@ void ObjectFactory::createRtdComponents(std::string spiDev, GpioIF* gpioComIF,
|
||||
void ObjectFactory::createScexComponents(std::string uartDev, PowerSwitchIF* pwrSwitcher,
|
||||
SdCardMountedIF& mountedIF, bool onImmediately,
|
||||
std::optional<power::Switch_t> switchId) {
|
||||
auto* cookie = new SerialCookie(objects::SCEX, uartDev, uart::SCEX_BAUD, 4096);
|
||||
auto* cookie = new SerialCookie(objects::SCEX, uartDev, serial::SCEX_BAUD, 4096);
|
||||
cookie->setTwoStopBits();
|
||||
// cookie->setParityEven();
|
||||
auto scexUartReader = new ScexUartReader(objects::SCEX_UART_READER);
|
||||
|
@ -14,7 +14,10 @@
|
||||
|
||||
using namespace GOMSPACE;
|
||||
|
||||
CspComIF::CspComIF(object_id_t objectId) : SystemObject(objectId) {}
|
||||
CspComIF::CspComIF(object_id_t objectId, const char* routeTaskName, uint32_t routerRealTimePriority)
|
||||
: SystemObject(objectId),
|
||||
routerRealTimePriority(routerRealTimePriority),
|
||||
routerTaskName(routeTaskName) {}
|
||||
|
||||
CspComIF::~CspComIF() {}
|
||||
|
||||
@ -57,10 +60,8 @@ ReturnValue_t CspComIF::initializeInterface(CookieIF* cookie) {
|
||||
}
|
||||
|
||||
/* Start the route task */
|
||||
unsigned int task_stack_size = 500;
|
||||
unsigned int priority = 0;
|
||||
result = csp_route_start_task(task_stack_size, priority);
|
||||
if (result != CSP_ERR_NONE) {
|
||||
result = startRouterTask();
|
||||
if (result != returnvalue::OK) {
|
||||
sif::error << "Failed to start csp route task" << std::endl;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
@ -343,3 +344,55 @@ void CspComIF::initiatePingRequest(uint8_t cspAddress, uint16_t querySize) {
|
||||
memcpy(replyBuffer, &replyTime, sizeof(replyTime));
|
||||
iter->second.replyLen = sizeof(replyTime);
|
||||
}
|
||||
|
||||
ReturnValue_t CspComIF::startRouterTask() {
|
||||
pthread_attr_t attr;
|
||||
int res = pthread_attr_init(&attr);
|
||||
if (res) {
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
|
||||
pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_DETACHED);
|
||||
|
||||
res = pthread_attr_setinheritsched(&attr, PTHREAD_EXPLICIT_SCHED);
|
||||
if (res != 0) {
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
|
||||
// Set scheduling policy to SCHED_RR
|
||||
res = pthread_attr_setschedpolicy(&attr, SCHED_RR);
|
||||
if (res) {
|
||||
pthread_attr_destroy(&attr);
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
|
||||
struct sched_param sched_param;
|
||||
sched_param.sched_priority = routerRealTimePriority;
|
||||
res = pthread_attr_setschedparam(&attr, &sched_param);
|
||||
if (res) {
|
||||
pthread_attr_destroy(&attr);
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
|
||||
res = pthread_create(&routerTaskHandle, &attr, routerWorkWrapper, NULL);
|
||||
if (res) {
|
||||
pthread_attr_destroy(&attr);
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
|
||||
res = pthread_setname_np(routerTaskHandle, routerTaskName);
|
||||
if (res) {
|
||||
pthread_attr_destroy(&attr);
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
pthread_attr_destroy(&attr);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void* CspComIF::routerWorkWrapper(void* args) {
|
||||
/* Here there be routing */
|
||||
while (1) {
|
||||
csp_route_work(FIFO_TIMEOUT);
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
|
@ -2,9 +2,11 @@
|
||||
#define LINUX_CSP_CSPCOMIF_H_
|
||||
|
||||
#include <csp/csp.h>
|
||||
#include <csp/csp_autoconfig.h>
|
||||
#include <fsfw/devicehandlers/DeviceCommunicationIF.h>
|
||||
#include <fsfw/objectmanager/SystemObject.h>
|
||||
#include <fsfw/returnvalues/returnvalue.h>
|
||||
#include <pthread.h>
|
||||
|
||||
#include <unordered_map>
|
||||
#include <vector>
|
||||
@ -17,7 +19,7 @@
|
||||
*/
|
||||
class CspComIF : public DeviceCommunicationIF, public SystemObject {
|
||||
public:
|
||||
CspComIF(object_id_t objectId);
|
||||
CspComIF(object_id_t objectId, const char *routeTaskName, uint32_t routerRealTimePriority);
|
||||
virtual ~CspComIF();
|
||||
|
||||
ReturnValue_t initializeInterface(CookieIF *cookie) override;
|
||||
@ -27,6 +29,13 @@ class CspComIF : public DeviceCommunicationIF, public SystemObject {
|
||||
ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **readData, size_t *readLen) override;
|
||||
|
||||
private:
|
||||
#ifdef CSP_USE_RDP
|
||||
//! If RDP is enabled, the router needs to awake some times to check timeouts
|
||||
static constexpr uint32_t FIFO_TIMEOUT = 100;
|
||||
#else
|
||||
//! If no RDP, the router can sleep untill data arrives
|
||||
static constexpr uint32_t FIFO_TIMEOUT = CSP_MAX_DELAY;
|
||||
#endif
|
||||
/**
|
||||
* @brief This function initiates the CSP transfer.
|
||||
*
|
||||
@ -56,6 +65,10 @@ class CspComIF : public DeviceCommunicationIF, public SystemObject {
|
||||
/* This is the CSP address of the OBC. */
|
||||
node_t cspOwnAddress = 1;
|
||||
|
||||
pthread_t routerTaskHandle{};
|
||||
uint32_t routerRealTimePriority = 0;
|
||||
const char *routerTaskName;
|
||||
|
||||
/* Interface struct for csp protocol stack */
|
||||
csp_iface_t csp_if;
|
||||
char canInterface[5] = "can0";
|
||||
@ -72,6 +85,9 @@ class CspComIF : public DeviceCommunicationIF, public SystemObject {
|
||||
* @brief This function initiates the ping request.
|
||||
*/
|
||||
void initiatePingRequest(uint8_t cspAddress, uint16_t querySize);
|
||||
|
||||
ReturnValue_t startRouterTask();
|
||||
static void *routerWorkWrapper(void *args);
|
||||
};
|
||||
|
||||
#endif /* LINUX_CSP_CSPCOMIF_H_ */
|
||||
|
@ -221,7 +221,7 @@ ReturnValue_t AcsBoardPolling::sendMessage(CookieIF* cookie, const uint8_t* send
|
||||
}
|
||||
}
|
||||
if (state == InternalState::IDLE) {
|
||||
state = InternalState::BUSY;
|
||||
state = InternalState::IS_BUSY;
|
||||
}
|
||||
}
|
||||
semaphore->release();
|
||||
|
@ -20,7 +20,7 @@ class AcsBoardPolling : public SystemObject,
|
||||
ReturnValue_t initialize() override;
|
||||
|
||||
private:
|
||||
enum class InternalState { IDLE, BUSY } state = InternalState::IDLE;
|
||||
enum class InternalState { IDLE, IS_BUSY } state = InternalState::IDLE;
|
||||
MutexIF* ipcLock;
|
||||
static constexpr MutexIF::TimeoutType LOCK_TYPE = MutexIF::TimeoutType::WAITING;
|
||||
static constexpr uint32_t LOCK_TIMEOUT = 20;
|
||||
|
@ -11,7 +11,8 @@ target_sources(
|
||||
ScexDleParser.cpp
|
||||
ScexHelper.cpp
|
||||
RwPollingTask.cpp
|
||||
AcsBoardPolling.cpp)
|
||||
AcsBoardPolling.cpp
|
||||
SyrlinksComHandler.cpp)
|
||||
|
||||
add_subdirectory(ploc)
|
||||
|
||||
|
@ -245,7 +245,7 @@ ReturnValue_t ImtqPollingTask::sendMessage(CookieIF* cookie, const uint8_t* send
|
||||
if (state != InternalState::IDLE) {
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
state = InternalState::BUSY;
|
||||
state = InternalState::IS_BUSY;
|
||||
}
|
||||
semaphore->release();
|
||||
|
||||
|
@ -23,7 +23,7 @@ class ImtqPollingTask : public SystemObject,
|
||||
private:
|
||||
static constexpr ReturnValue_t NO_REPLY_AVAILABLE = returnvalue::makeCode(2, 0);
|
||||
|
||||
enum class InternalState { IDLE, BUSY } state = InternalState::IDLE;
|
||||
enum class InternalState { IDLE, IS_BUSY } state = InternalState::IDLE;
|
||||
imtq::RequestType currentRequest = imtq::RequestType::MEASURE_NO_ACTUATION;
|
||||
|
||||
SemaphoreIF* semaphore;
|
||||
|
@ -147,7 +147,7 @@ ReturnValue_t RwPollingTask::sendMessage(CookieIF* cookie, const uint8_t* sendDa
|
||||
rwCookie->currentRampTime = rampTime;
|
||||
rwCookie->specialRequest = specialRequest;
|
||||
if (state == InternalState::IDLE) {
|
||||
state = InternalState::BUSY;
|
||||
state = InternalState::IS_BUSY;
|
||||
semaphore->release();
|
||||
}
|
||||
}
|
||||
|
@ -41,7 +41,7 @@ class RwPollingTask : public SystemObject, public ExecutableObjectIF, public Dev
|
||||
ReturnValue_t initialize() override;
|
||||
|
||||
private:
|
||||
enum class InternalState { IDLE, BUSY } state = InternalState::IDLE;
|
||||
enum class InternalState { IDLE, IS_BUSY } state = InternalState::IDLE;
|
||||
SemaphoreIF* semaphore;
|
||||
bool debugMode = false;
|
||||
bool modeAndSpeedWasSet = false;
|
||||
|
@ -98,11 +98,11 @@ ReturnValue_t ScexUartReader::initializeInterface(CookieIF *cookie) {
|
||||
}
|
||||
// Setting up UART parameters
|
||||
tty.c_cflag &= ~PARENB; // Clear parity bit
|
||||
uart::setStopbits(tty, uartCookie->getStopBits());
|
||||
uart::setBitsPerWord(tty, BitsPerWord::BITS_8);
|
||||
serial::setStopbits(tty, uartCookie->getStopBits());
|
||||
serial::setBitsPerWord(tty, BitsPerWord::BITS_8);
|
||||
tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control
|
||||
uart::enableRead(tty);
|
||||
uart::ignoreCtrlLines(tty);
|
||||
serial::enableRead(tty);
|
||||
serial::ignoreCtrlLines(tty);
|
||||
|
||||
// Use non-canonical mode and clear echo flag
|
||||
tty.c_lflag &= ~(ICANON | ECHO);
|
||||
@ -111,7 +111,7 @@ ReturnValue_t ScexUartReader::initializeInterface(CookieIF *cookie) {
|
||||
tty.c_cc[VTIME] = 0;
|
||||
tty.c_cc[VMIN] = 0;
|
||||
|
||||
uart::setBaudrate(tty, uartCookie->getBaudrate());
|
||||
serial::setBaudrate(tty, uartCookie->getBaudrate());
|
||||
if (tcsetattr(serialPort, TCSANOW, &tty) != 0) {
|
||||
sif::warning << "ScexUartReader::initializeInterface: tcsetattr call failed with error ["
|
||||
<< errno << ", " << strerror(errno) << std::endl;
|
||||
@ -148,8 +148,7 @@ ReturnValue_t ScexUartReader::sendMessage(CookieIF *cookie, const uint8_t *sendD
|
||||
}
|
||||
size_t bytesWritten = write(serialPort, cmdbuf.data(), encodedLen);
|
||||
if (bytesWritten != encodedLen) {
|
||||
sif::warning << "ScexUartReader::sendMessage: Sending ping command to solar experiment failed"
|
||||
<< std::endl;
|
||||
sif::warning << "ScexUartReader::sendMessage: Sending command failed" << std::endl;
|
||||
return FAILED;
|
||||
}
|
||||
|
||||
|
@ -77,7 +77,7 @@ ReturnValue_t SusPolling::sendMessage(CookieIF* cookie, const uint8_t* sendData,
|
||||
susDevs[susIdx].mode = susReq->mode;
|
||||
}
|
||||
if (state == InternalState::IDLE) {
|
||||
state = InternalState::BUSY;
|
||||
state = InternalState::IS_BUSY;
|
||||
semaphore->release();
|
||||
}
|
||||
return OK;
|
||||
|
@ -18,7 +18,7 @@ class SusPolling : public SystemObject, public ExecutableObjectIF, public Device
|
||||
ReturnValue_t initialize() override;
|
||||
|
||||
private:
|
||||
enum class InternalState { IDLE, BUSY } state = InternalState::IDLE;
|
||||
enum class InternalState { IDLE, IS_BUSY } state = InternalState::IDLE;
|
||||
|
||||
struct SusDev {
|
||||
SpiCookie* cookie = nullptr;
|
||||
|
209
linux/devices/SyrlinksComHandler.cpp
Normal file
209
linux/devices/SyrlinksComHandler.cpp
Normal file
@ -0,0 +1,209 @@
|
||||
#include "SyrlinksComHandler.h"
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <fsfw/ipc/MutexGuard.h>
|
||||
#include <fsfw/tasks/SemaphoreFactory.h>
|
||||
#include <fsfw/tasks/TaskFactory.h>
|
||||
#include <fsfw/timemanager/Stopwatch.h>
|
||||
#include <fsfw_hal/linux/serial/SerialCookie.h>
|
||||
#include <fsfw_hal/linux/serial/helper.h>
|
||||
#include <unistd.h>
|
||||
|
||||
using namespace returnvalue;
|
||||
|
||||
SyrlinksComHandler::SyrlinksComHandler(object_id_t objectId)
|
||||
: SystemObject(objectId), ringBuf(2048, true) {
|
||||
lock = MutexFactory::instance()->createMutex();
|
||||
semaphore = SemaphoreFactory::instance()->createBinarySemaphore();
|
||||
semaphore->acquire();
|
||||
}
|
||||
|
||||
ReturnValue_t SyrlinksComHandler::performOperation(uint8_t opCode) {
|
||||
while (true) {
|
||||
lock->lockMutex();
|
||||
state = State::SLEEPING;
|
||||
lock->unlockMutex();
|
||||
semaphore->acquire();
|
||||
// Stopwatch watch;
|
||||
readOneReply();
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t SyrlinksComHandler::initializeInterface(CookieIF *cookie) {
|
||||
if (cookie == nullptr) {
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
SerialCookie *serCookie = dynamic_cast<SerialCookie *>(cookie);
|
||||
if (serCookie == nullptr) {
|
||||
return DeviceCommunicationIF::INVALID_COOKIE_TYPE;
|
||||
}
|
||||
// comCookie = serCookie;
|
||||
std::string devname = serCookie->getDeviceFile();
|
||||
/* Get file descriptor */
|
||||
serialPort = open(devname.c_str(), O_RDWR);
|
||||
if (serialPort < 0) {
|
||||
sif::warning << "SyrlinksComHandler: open call failed with error [" << errno << ", "
|
||||
<< strerror(errno) << std::endl;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
// Setting up UART parameters
|
||||
serial::setStopbits(tty, serCookie->getStopBits());
|
||||
serial::setParity(tty, serCookie->getParity());
|
||||
serial::setBitsPerWord(tty, BitsPerWord::BITS_8);
|
||||
tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control
|
||||
serial::enableRead(tty);
|
||||
serial::ignoreCtrlLines(tty);
|
||||
|
||||
// Use non-canonical mode and clear echo flag
|
||||
tty.c_lflag &= ~(ICANON | ECHO);
|
||||
|
||||
// Non-blocking mode, use polling
|
||||
tty.c_cc[VTIME] = 0;
|
||||
tty.c_cc[VMIN] = 0;
|
||||
|
||||
serial::setBaudrate(tty, serCookie->getBaudrate());
|
||||
if (tcsetattr(serialPort, TCSANOW, &tty) != 0) {
|
||||
sif::warning << "ScexUartReader::initializeInterface: tcsetattr call failed with error ["
|
||||
<< errno << ", " << strerror(errno) << std::endl;
|
||||
}
|
||||
// Flush received and unread data
|
||||
tcflush(serialPort, TCIOFLUSH);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t SyrlinksComHandler::sendMessage(CookieIF *cookie, const uint8_t *sendData,
|
||||
size_t sendLen) {
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
if (state != State::SLEEPING) {
|
||||
return BUSY;
|
||||
}
|
||||
}
|
||||
serial::flushRxBuf(serialPort);
|
||||
|
||||
ssize_t writtenBytes = write(serialPort, sendData, sendLen);
|
||||
if (writtenBytes != static_cast<ssize_t>(sendLen)) {
|
||||
sif::warning << "StrComHandler: Sending packet failed" << std::endl;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
state = State::ACTIVE;
|
||||
}
|
||||
semaphore->release();
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t SyrlinksComHandler::getSendSuccess(CookieIF *cookie) { return returnvalue::OK; }
|
||||
|
||||
ReturnValue_t SyrlinksComHandler::requestReceiveMessage(CookieIF *cookie, size_t requestLen) {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t SyrlinksComHandler::handleSerialReception() {
|
||||
ssize_t bytesRead = read(serialPort, reinterpret_cast<void *>(recBuf.data()),
|
||||
static_cast<unsigned int>(recBuf.size()));
|
||||
if (bytesRead == 0) {
|
||||
return NO_SERIAL_DATA_READ;
|
||||
} else if (bytesRead < 0) {
|
||||
sif::warning << "SyrlinksComHandler: read call failed with error [" << errno << ", "
|
||||
<< strerror(errno) << "]" << std::endl;
|
||||
return FAILED;
|
||||
} else if (bytesRead >= static_cast<int>(recBuf.size())) {
|
||||
sif::error << "SyrlinksComHandler: Receive buffer too small for " << bytesRead << " bytes"
|
||||
<< std::endl;
|
||||
return FAILED;
|
||||
} else if (bytesRead > 0) {
|
||||
// sif::debug << "Received " << bytesRead << " bytes from the Syrlinks" << std::endl;
|
||||
// arrayprinter::print(recBuf.data(), bytesRead);
|
||||
ringBuf.writeData(recBuf.data(), bytesRead);
|
||||
}
|
||||
return OK;
|
||||
}
|
||||
|
||||
ReturnValue_t SyrlinksComHandler::readReceivedMessage(CookieIF *cookie, uint8_t **buffer,
|
||||
size_t *size) {
|
||||
MutexGuard mg(lock);
|
||||
if (replyResult != returnvalue::OK) {
|
||||
ReturnValue_t tmp = replyResult;
|
||||
replyResult = returnvalue::OK;
|
||||
return tmp;
|
||||
}
|
||||
if (replyLen == 0) {
|
||||
*size = 0;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
*buffer = ipcBuf.data();
|
||||
*size = replyLen;
|
||||
replyLen = 0;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t SyrlinksComHandler::readOneReply() {
|
||||
ReturnValue_t result;
|
||||
uint32_t nextDelayMs = 1;
|
||||
replyTimeout.resetTimer();
|
||||
while (true) {
|
||||
handleSerialReception();
|
||||
result = tryReadingOneSyrlinksReply();
|
||||
if (result == returnvalue::OK) {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
if (replyTimeout.hasTimedOut()) {
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
replyResult = DeviceCommunicationIF::NO_REPLY_RECEIVED;
|
||||
}
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
TaskFactory::delayTask(nextDelayMs);
|
||||
if (nextDelayMs < 32) {
|
||||
nextDelayMs *= 2;
|
||||
}
|
||||
}
|
||||
}
|
||||
ReturnValue_t SyrlinksComHandler::tryReadingOneSyrlinksReply() {
|
||||
size_t bytesToRead = ringBuf.getAvailableReadData();
|
||||
if (bytesToRead == 0) {
|
||||
return NO_PACKET_FOUND;
|
||||
}
|
||||
bool startMarkerFound = false;
|
||||
size_t startIdx = 0;
|
||||
ringBuf.readData(recBuf.data(), bytesToRead);
|
||||
for (size_t idx = 0; idx < bytesToRead; idx++) {
|
||||
if (recBuf[idx] == START_MARKER) {
|
||||
if (startMarkerFound) {
|
||||
// Probably lost a packet. Discard broken packet.
|
||||
sif::warning << "SyrlinksComHandler: Detected 2 consecutive start markers" << std::endl;
|
||||
ringBuf.deleteData(idx);
|
||||
} else {
|
||||
startMarkerFound = true;
|
||||
startIdx = idx;
|
||||
}
|
||||
}
|
||||
if (recBuf[idx] == END_MARKER) {
|
||||
if (startMarkerFound) {
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
replyLen = idx - startIdx + 1;
|
||||
}
|
||||
// Copy detected packet to IPC buffer so it can be passed back to the device handler.
|
||||
if (replyLen > ipcBuf.size()) {
|
||||
sif::error << "SyrlinksComHandler: Detected reply too large" << std::endl;
|
||||
ringBuf.deleteData(idx);
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
// sif::debug << "Detected Syrlinks reply with length " << replyLen << std::endl;
|
||||
std::memcpy(ipcBuf.data(), recBuf.data() + startIdx, replyLen);
|
||||
ringBuf.deleteData(idx + 1);
|
||||
return returnvalue::OK;
|
||||
} else {
|
||||
// Probably lost a packet. Discard broken packet.
|
||||
sif::warning << "SyrlinksComHandler: Detected 2 consecutive end markers" << std::endl;
|
||||
ringBuf.deleteData(idx + 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
return NO_PACKET_FOUND;
|
||||
}
|
52
linux/devices/SyrlinksComHandler.h
Normal file
52
linux/devices/SyrlinksComHandler.h
Normal file
@ -0,0 +1,52 @@
|
||||
#ifndef LINUX_DEVICES_SYRLINKSCOMHANDLER_H_
|
||||
#define LINUX_DEVICES_SYRLINKSCOMHANDLER_H_
|
||||
|
||||
#include <fsfw/container/SimpleRingBuffer.h>
|
||||
#include <fsfw/devicehandlers/DeviceCommunicationIF.h>
|
||||
#include <fsfw/objectmanager/SystemObject.h>
|
||||
#include <fsfw/tasks/ExecutableObjectIF.h>
|
||||
#include <fsfw/tasks/SemaphoreIF.h>
|
||||
#include <termios.h>
|
||||
|
||||
class SyrlinksComHandler : public DeviceCommunicationIF,
|
||||
public ExecutableObjectIF,
|
||||
public SystemObject {
|
||||
public:
|
||||
SyrlinksComHandler(object_id_t objectId);
|
||||
|
||||
private:
|
||||
static constexpr char START_MARKER = '<';
|
||||
static constexpr char END_MARKER = '>';
|
||||
|
||||
//! [EXPORT] : [SKIP]
|
||||
static constexpr ReturnValue_t NO_SERIAL_DATA_READ = returnvalue::makeCode(2, 0);
|
||||
static constexpr ReturnValue_t NO_PACKET_FOUND = returnvalue::makeCode(2, 1);
|
||||
|
||||
enum class State { SLEEPING, ACTIVE } state = State::SLEEPING;
|
||||
|
||||
MutexIF *lock;
|
||||
SemaphoreIF *semaphore;
|
||||
int serialPort = 0;
|
||||
struct termios tty {};
|
||||
Countdown replyTimeout = Countdown(2000);
|
||||
std::array<uint8_t, 2048> recBuf{};
|
||||
SimpleRingBuffer ringBuf;
|
||||
std::array<uint8_t, 1024> ipcBuf{};
|
||||
size_t replyLen = 0;
|
||||
ReturnValue_t replyResult = returnvalue::OK;
|
||||
|
||||
ReturnValue_t handleSerialReception();
|
||||
|
||||
ReturnValue_t performOperation(uint8_t opCode) override;
|
||||
|
||||
ReturnValue_t initializeInterface(CookieIF *cookie) override;
|
||||
ReturnValue_t sendMessage(CookieIF *cookie, const uint8_t *sendData, size_t sendLen) override;
|
||||
ReturnValue_t getSendSuccess(CookieIF *cookie) override;
|
||||
ReturnValue_t requestReceiveMessage(CookieIF *cookie, size_t requestLen) override;
|
||||
ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) override;
|
||||
|
||||
ReturnValue_t readOneReply();
|
||||
ReturnValue_t tryReadingOneSyrlinksReply();
|
||||
};
|
||||
|
||||
#endif /* LINUX_DEVICES_SYRLINKSCOMHANDLER_H_ */
|
@ -58,12 +58,12 @@ ReturnValue_t PlocSupvUartManager::initializeInterface(CookieIF* cookie) {
|
||||
}
|
||||
// Setting up UART parameters
|
||||
tty.c_cflag &= ~PARENB; // Clear parity bit
|
||||
uart::setParity(tty, uartCookie->getParity());
|
||||
uart::setStopbits(tty, uartCookie->getStopBits());
|
||||
uart::setBitsPerWord(tty, BitsPerWord::BITS_8);
|
||||
serial::setParity(tty, uartCookie->getParity());
|
||||
serial::setStopbits(tty, uartCookie->getStopBits());
|
||||
serial::setBitsPerWord(tty, BitsPerWord::BITS_8);
|
||||
tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control
|
||||
uart::enableRead(tty);
|
||||
uart::ignoreCtrlLines(tty);
|
||||
serial::enableRead(tty);
|
||||
serial::ignoreCtrlLines(tty);
|
||||
|
||||
// Use non-canonical mode and clear echo flag
|
||||
tty.c_lflag &= ~(ICANON | ECHO);
|
||||
@ -72,7 +72,7 @@ ReturnValue_t PlocSupvUartManager::initializeInterface(CookieIF* cookie) {
|
||||
tty.c_cc[VTIME] = 2;
|
||||
tty.c_cc[VMIN] = 0;
|
||||
|
||||
uart::setBaudrate(tty, uartCookie->getBaudrate());
|
||||
serial::setBaudrate(tty, uartCookie->getBaudrate());
|
||||
if (tcsetattr(serialPort, TCSANOW, &tty) != 0) {
|
||||
sif::warning << "PlocSupvUartManager::initializeInterface: tcsetattr call failed with error ["
|
||||
<< errno << ", " << strerror(errno) << std::endl;
|
||||
|
@ -246,9 +246,9 @@ class PlocSupvUartManager : public DeviceCommunicationIF,
|
||||
std::array<uint8_t, 2048> recBuf = {};
|
||||
std::array<uint8_t, 2048> encodedBuf = {};
|
||||
std::array<uint8_t, 1200> decodedBuf = {};
|
||||
std::array<uint8_t, 1200> ipcBuffer = {};
|
||||
SimpleRingBuffer decodedRingBuf;
|
||||
FIFO<size_t, MAX_STORED_DECODED_PACKETS> decodedQueue;
|
||||
std::array<uint8_t, 1200> ipcBuffer = {};
|
||||
SimpleRingBuffer ipcRingBuf;
|
||||
FIFO<size_t, MAX_STORED_DECODED_PACKETS> ipcQueue;
|
||||
|
||||
|
@ -1,39 +1,39 @@
|
||||
#include "ArcsecDatalinkLayer.h"
|
||||
|
||||
ArcsecDatalinkLayer::ArcsecDatalinkLayer() { slipInit(); }
|
||||
ArcsecDatalinkLayer::ArcsecDatalinkLayer() : decodeRingBuf(BUFFER_LENGTHS, true) { slipInit(); }
|
||||
|
||||
ArcsecDatalinkLayer::~ArcsecDatalinkLayer() {}
|
||||
|
||||
void ArcsecDatalinkLayer::slipInit() {
|
||||
slipInfo.buffer = rxBuffer;
|
||||
slipInfo.maxlength = startracker::MAX_FRAME_SIZE;
|
||||
slipInfo.length = 0;
|
||||
slipInfo.unescape_next = 0;
|
||||
slipInfo.prev_state = SLIP_COMPLETE;
|
||||
}
|
||||
|
||||
ReturnValue_t ArcsecDatalinkLayer::decodeFrame(const uint8_t* rawData, size_t rawDataSize,
|
||||
size_t* bytesLeft) {
|
||||
size_t bytePos = 0;
|
||||
for (bytePos = 0; bytePos < rawDataSize; bytePos++) {
|
||||
ReturnValue_t ArcsecDatalinkLayer::checkRingBufForFrame(const uint8_t** decodedFrame,
|
||||
size_t& frameLen) {
|
||||
size_t currentLen = decodeRingBuf.getAvailableReadData();
|
||||
if (currentLen == 0) {
|
||||
return DEC_IN_PROGRESS;
|
||||
}
|
||||
decodeRingBuf.readData(rxAnalysisBuffer, currentLen);
|
||||
for (size_t idx = 0; idx < currentLen; idx++) {
|
||||
enum arc_dec_result decResult =
|
||||
arc_transport_decode_body(*(rawData + bytePos), &slipInfo, decodedFrame, &decFrameSize);
|
||||
*bytesLeft = rawDataSize - bytePos - 1;
|
||||
arc_transport_decode_body(rxAnalysisBuffer[idx], &slipInfo, decodedRxFrame, &rxFrameSize);
|
||||
switch (decResult) {
|
||||
case ARC_DEC_INPROGRESS: {
|
||||
if (bytePos == rawDataSize - 1) {
|
||||
return DEC_IN_PROGRESS;
|
||||
}
|
||||
continue;
|
||||
break;
|
||||
}
|
||||
case ARC_DEC_ERROR_FRAME_SHORT:
|
||||
case ARC_DEC_ERROR_FRAME_SHORT: {
|
||||
decodeRingBuf.deleteData(idx);
|
||||
return REPLY_TOO_SHORT;
|
||||
}
|
||||
case ARC_DEC_ERROR_CHECKSUM:
|
||||
decodeRingBuf.deleteData(idx);
|
||||
return CRC_FAILURE;
|
||||
case ARC_DEC_ASYNC:
|
||||
case ARC_DEC_SYNC: {
|
||||
// Reset length of SLIP struct for next frame
|
||||
slipInfo.length = 0;
|
||||
if (decodedFrame != nullptr) {
|
||||
*decodedFrame = decodedRxFrame;
|
||||
}
|
||||
frameLen = rxFrameSize;
|
||||
decodeRingBuf.deleteData(idx);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
default:
|
||||
@ -42,21 +42,32 @@ ReturnValue_t ArcsecDatalinkLayer::decodeFrame(const uint8_t* rawData, size_t ra
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
}
|
||||
return returnvalue::FAILED;
|
||||
decodeRingBuf.deleteData(currentLen);
|
||||
return DEC_IN_PROGRESS;
|
||||
}
|
||||
|
||||
uint8_t ArcsecDatalinkLayer::getReplyFrameType() { return decodedFrame[0]; }
|
||||
|
||||
const uint8_t* ArcsecDatalinkLayer::getReply() { return &decodedFrame[1]; }
|
||||
|
||||
void ArcsecDatalinkLayer::encodeFrame(const uint8_t* data, uint32_t length) {
|
||||
arc_transport_encode_body(data, length, encBuffer, &encFrameSize);
|
||||
ReturnValue_t ArcsecDatalinkLayer::feedData(const uint8_t* rawData, size_t rawDataLen) {
|
||||
if (rawDataLen > 4096) {
|
||||
sif::error << "ArcsecDatalinklayer: Can not write more than 4096 bytes to ring buffer"
|
||||
<< std::endl;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
return decodeRingBuf.writeData(rawData, rawDataLen);
|
||||
}
|
||||
|
||||
uint8_t* ArcsecDatalinkLayer::getEncodedFrame() { return encBuffer; }
|
||||
void ArcsecDatalinkLayer::reset() {
|
||||
slipInit();
|
||||
decodeRingBuf.clear();
|
||||
}
|
||||
|
||||
uint32_t ArcsecDatalinkLayer::getEncodedLength() { return encFrameSize; }
|
||||
void ArcsecDatalinkLayer::slipInit() {
|
||||
slip_decode_init(rxBufferArc, sizeof(rxBufferArc), &slipInfo);
|
||||
}
|
||||
|
||||
uint8_t ArcsecDatalinkLayer::getStatusField() { return *(decodedFrame + STATUS_OFFSET); }
|
||||
|
||||
uint8_t ArcsecDatalinkLayer::getId() { return *(decodedFrame + ID_OFFSET); }
|
||||
void ArcsecDatalinkLayer::encodeFrame(const uint8_t* data, size_t length, const uint8_t** txFrame,
|
||||
size_t& size) {
|
||||
arc_transport_encode_body(data, length, txEncoded, &size);
|
||||
if (txFrame != nullptr) {
|
||||
*txFrame = txEncoded;
|
||||
}
|
||||
}
|
||||
|
@ -1,14 +1,14 @@
|
||||
#ifndef BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_
|
||||
#define BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_
|
||||
|
||||
#include <fsfw/container/SimpleRingBuffer.h>
|
||||
#include <fsfw/devicehandlers/CookieIF.h>
|
||||
|
||||
#include "arcsec/common/misc.h"
|
||||
#include "eive/resultClassIds.h"
|
||||
#include "fsfw/returnvalues/returnvalue.h"
|
||||
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
|
||||
|
||||
extern "C" {
|
||||
#include "common/misc.h"
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Helper class to handle the datalinklayer of replies from the star tracker of arcsec.
|
||||
*/
|
||||
@ -25,17 +25,30 @@ class ArcsecDatalinkLayer {
|
||||
|
||||
static const uint8_t STATUS_OK = 0;
|
||||
|
||||
static constexpr size_t BUFFER_LENGTHS = 4096;
|
||||
|
||||
ArcsecDatalinkLayer();
|
||||
virtual ~ArcsecDatalinkLayer();
|
||||
|
||||
/**
|
||||
* @brief Applies decoding to data referenced by rawData pointer
|
||||
*
|
||||
* @param rawData Pointer to raw data received from star tracker
|
||||
* @param rawDataSize Size of raw data stream
|
||||
* @param remainingBytes Number of bytes left
|
||||
* Feed received data to the internal ring buffer.
|
||||
* @param rawData
|
||||
* @param rawDataLen
|
||||
* @return
|
||||
*/
|
||||
ReturnValue_t decodeFrame(const uint8_t* rawData, size_t rawDataSize, size_t* bytesLeft);
|
||||
ReturnValue_t feedData(const uint8_t* rawData, size_t rawDataLen);
|
||||
|
||||
/**
|
||||
* Runs the arcsec datalink layer decoding algorithm on the data in the ring buffer, decoding
|
||||
* frames in the process.
|
||||
* @param decodedFrame
|
||||
* @param frameLen
|
||||
* @return
|
||||
* - returnvalue::OK if a frame was found
|
||||
* - DEC_IN_PROGRESS if frame decoding is in progress
|
||||
* - Anything else is a decoding error
|
||||
*/
|
||||
ReturnValue_t checkRingBufForFrame(const uint8_t** decodedFrame, size_t& frameLen);
|
||||
|
||||
/**
|
||||
* @brief SLIP encodes data pointed to by data pointer.
|
||||
@ -43,53 +56,31 @@ class ArcsecDatalinkLayer {
|
||||
* @param data Pointer to data to encode
|
||||
* @param length Length of buffer to encode
|
||||
*/
|
||||
void encodeFrame(const uint8_t* data, uint32_t length);
|
||||
void encodeFrame(const uint8_t* data, size_t length, const uint8_t** txFrame, size_t& frameLen);
|
||||
|
||||
/**
|
||||
* @brief Returns the frame type field of a decoded frame.
|
||||
*/
|
||||
uint8_t getReplyFrameType();
|
||||
|
||||
/**
|
||||
* @brief Returns pointer to reply packet (first entry normally action ID, telemetry ID etc.)
|
||||
*/
|
||||
const uint8_t* getReply();
|
||||
|
||||
/**
|
||||
* @brief Returns size of encoded frame
|
||||
*/
|
||||
uint32_t getEncodedLength();
|
||||
|
||||
/**
|
||||
* @brief Returns pointer to encoded frame
|
||||
*/
|
||||
uint8_t* getEncodedFrame();
|
||||
|
||||
/**
|
||||
* @brief Returns status of reply
|
||||
*/
|
||||
uint8_t getStatusField();
|
||||
|
||||
/**
|
||||
* @brief Returns ID of reply
|
||||
*/
|
||||
uint8_t getId();
|
||||
void reset();
|
||||
|
||||
private:
|
||||
static const uint8_t ID_OFFSET = 1;
|
||||
static const uint8_t STATUS_OFFSET = 2;
|
||||
|
||||
// Used by arcsec slip decoding function process received data
|
||||
uint8_t rxBuffer[startracker::MAX_FRAME_SIZE];
|
||||
// User to buffer and analyse data and allow feeding and checking for frames asychronously.
|
||||
SimpleRingBuffer decodeRingBuf;
|
||||
uint8_t rxAnalysisBuffer[BUFFER_LENGTHS];
|
||||
|
||||
// Used by arcsec slip decoding function to process received data. This should only be written
|
||||
// to or read from by arcsec functions!
|
||||
uint8_t rxBufferArc[startracker::MAX_FRAME_SIZE];
|
||||
// Decoded frame will be copied to this buffer
|
||||
uint8_t decodedFrame[startracker::MAX_FRAME_SIZE];
|
||||
uint8_t decodedRxFrame[startracker::MAX_FRAME_SIZE];
|
||||
// Size of decoded frame
|
||||
uint32_t rxFrameSize = 0;
|
||||
|
||||
// Buffer where encoded frames will be stored. First byte of encoded frame represents type of
|
||||
// reply
|
||||
uint8_t encBuffer[startracker::MAX_FRAME_SIZE * 2 + 2];
|
||||
// Size of decoded frame
|
||||
uint32_t decFrameSize = 0;
|
||||
uint8_t txEncoded[startracker::MAX_FRAME_SIZE * 2 + 2];
|
||||
// Size of encoded frame
|
||||
uint32_t encFrameSize = 0;
|
||||
uint32_t txFrameSize = 0;
|
||||
|
||||
slip_decode_state slipInfo;
|
||||
|
||||
|
@ -1,17 +1,10 @@
|
||||
#include "ArcsecJsonParamBase.h"
|
||||
|
||||
#include "ArcsecJsonKeys.h"
|
||||
#include "arcsecJsonKeys.h"
|
||||
|
||||
ArcsecJsonParamBase::ArcsecJsonParamBase(std::string setName) : setName(setName) {}
|
||||
|
||||
ReturnValue_t ArcsecJsonParamBase::create(std::string fullname, uint8_t* buffer) {
|
||||
// ReturnValue_t result = returnvalue::OK;
|
||||
// result = init(fullname);
|
||||
// if (result != returnvalue::OK) {
|
||||
// sif::warning << "ArcsecJsonParamBase::create: Failed to init parameter command for set "
|
||||
// << setName << std::endl;
|
||||
// return result;
|
||||
// }
|
||||
ReturnValue_t ArcsecJsonParamBase::create(uint8_t* buffer) {
|
||||
ReturnValue_t result = createCommand(buffer);
|
||||
if (result != returnvalue::OK) {
|
||||
sif::warning << "ArcsecJsonParamBase::create: Failed to create parameter command for set "
|
||||
|
@ -5,15 +5,12 @@
|
||||
#include <fstream>
|
||||
#include <nlohmann/json.hpp>
|
||||
|
||||
#include "arcsec/common/generated/tmtcstructs.h"
|
||||
#include "arcsec/common/genericstructs.h"
|
||||
#include "eive/resultClassIds.h"
|
||||
#include "fsfw/returnvalues/returnvalue.h"
|
||||
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
|
||||
|
||||
extern "C" {
|
||||
#include "thirdparty/arcsec_star_tracker/common/generated/tmtcstructs.h"
|
||||
#include "thirdparty/arcsec_star_tracker/common/genericstructs.h"
|
||||
}
|
||||
|
||||
using json = nlohmann::json;
|
||||
|
||||
/**
|
||||
@ -59,7 +56,7 @@ class ArcsecJsonParamBase {
|
||||
* parameter set.
|
||||
* @param buffer Pointer to the buffer the command will be written to
|
||||
*/
|
||||
ReturnValue_t create(std::string fullname, uint8_t* buffer);
|
||||
ReturnValue_t create(uint8_t* buffer);
|
||||
|
||||
/**
|
||||
* @brief Returns the size of the parameter command.
|
||||
|
@ -1,4 +1,4 @@
|
||||
target_sources(
|
||||
${OBSW_NAME}
|
||||
PRIVATE StarTrackerHandler.cpp StarTrackerJsonCommands.cpp
|
||||
ArcsecDatalinkLayer.cpp ArcsecJsonParamBase.cpp StrHelper.cpp)
|
||||
PRIVATE StarTrackerHandler.cpp strJsonCommands.cpp ArcsecDatalinkLayer.cpp
|
||||
ArcsecJsonParamBase.cpp StrComHandler.cpp helpers.cpp)
|
||||
|
@ -1,5 +1,8 @@
|
||||
#include "StarTrackerHandler.h"
|
||||
|
||||
#include <arcsec/client/generated/actionreq.h>
|
||||
#include <arcsec/client/generated/parameter.h>
|
||||
#include <arcsec/client/generated/telemetry.h>
|
||||
#include <fsfw/ipc/QueueFactory.h>
|
||||
#include <fsfw/timemanager/Stopwatch.h>
|
||||
|
||||
@ -8,19 +11,14 @@
|
||||
#include <thread>
|
||||
|
||||
#include "OBSWConfig.h"
|
||||
#include "StarTrackerJsonCommands.h"
|
||||
extern "C" {
|
||||
#include <thirdparty/arcsec_star_tracker/client/generated/actionreq.h>
|
||||
#include <thirdparty/arcsec_star_tracker/client/generated/parameter.h>
|
||||
#include <thirdparty/arcsec_star_tracker/client/generated/telemetry.h>
|
||||
|
||||
#include "common/misc.h"
|
||||
}
|
||||
#include "arcsec/common/misc.h"
|
||||
#include "helpers.h"
|
||||
#include "strJsonCommands.h"
|
||||
|
||||
std::atomic_bool JCFG_DONE(false);
|
||||
|
||||
StarTrackerHandler::StarTrackerHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie,
|
||||
const char* jsonFileStr, StrHelper* strHelper,
|
||||
const char* jsonFileStr, StrComHandler* strHelper,
|
||||
power::Switch_t powerSwitch)
|
||||
: DeviceHandlerBase(objectId, comIF, comCookie),
|
||||
temperatureSet(this),
|
||||
@ -84,8 +82,8 @@ ReturnValue_t StarTrackerHandler::initialize() {
|
||||
return result;
|
||||
}
|
||||
result = manager->subscribeToEventRange(eventQueue->getId(),
|
||||
event::getEventId(StrHelper::IMAGE_UPLOAD_FAILED),
|
||||
event::getEventId(StrHelper::FIRMWARE_UPDATE_FAILED));
|
||||
event::getEventId(StrComHandler::IMAGE_UPLOAD_FAILED),
|
||||
event::getEventId(StrComHandler::FIRMWARE_UPDATE_FAILED));
|
||||
if (result != returnvalue::OK) {
|
||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||
sif::warning << "StarTrackerHandler::initialize: Failed to subscribe to events from "
|
||||
@ -95,11 +93,6 @@ ReturnValue_t StarTrackerHandler::initialize() {
|
||||
return ObjectManagerIF::CHILD_INIT_FAILED;
|
||||
}
|
||||
|
||||
result = strHelper->setComIF(communicationInterface);
|
||||
if (result != returnvalue::OK) {
|
||||
return ObjectManagerIF::CHILD_INIT_FAILED;
|
||||
}
|
||||
strHelper->setComCookie(comCookie);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
@ -828,41 +821,36 @@ ReturnValue_t StarTrackerHandler::scanForReply(const uint8_t* start, size_t rema
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
size_t bytesLeft = 0;
|
||||
|
||||
result = dataLinkLayer.decodeFrame(start, remainingSize, &bytesLeft);
|
||||
switch (result) {
|
||||
case ArcsecDatalinkLayer::DEC_IN_PROGRESS: {
|
||||
remainingSize = bytesLeft;
|
||||
// Need a second doSendRead pass to reaa in whole packet
|
||||
return IGNORE_REPLY_DATA;
|
||||
}
|
||||
case returnvalue::OK: {
|
||||
break;
|
||||
}
|
||||
default:
|
||||
remainingSize = bytesLeft;
|
||||
return result;
|
||||
if (remainingSize == 0) {
|
||||
*foundLen = remainingSize;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
if (remainingSize < 3) {
|
||||
sif::error << "StarTrackerHandler: Reply packet with length less than 3 is invalid"
|
||||
<< std::endl;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
|
||||
switch (dataLinkLayer.getReplyFrameType()) {
|
||||
switch (str::getReplyFrameType(start)) {
|
||||
case TMTC_ACTIONREPLY: {
|
||||
*foundLen = remainingSize - bytesLeft;
|
||||
result = scanForActionReply(foundId);
|
||||
result = scanForActionReply(str::getId(start), foundId);
|
||||
break;
|
||||
}
|
||||
case TMTC_SETPARAMREPLY: {
|
||||
*foundLen = remainingSize - bytesLeft;
|
||||
result = scanForSetParameterReply(foundId);
|
||||
result = scanForSetParameterReply(str::getId(start), foundId);
|
||||
break;
|
||||
}
|
||||
case TMTC_PARAMREPLY: {
|
||||
*foundLen = remainingSize - bytesLeft;
|
||||
result = scanForGetParameterReply(foundId);
|
||||
result = scanForGetParameterReply(str::getId(start), foundId);
|
||||
break;
|
||||
}
|
||||
case TMTC_TELEMETRYREPLYA:
|
||||
case TMTC_TELEMETRYREPLY: {
|
||||
*foundLen = remainingSize - bytesLeft;
|
||||
result = scanForTmReply(foundId);
|
||||
result = scanForTmReply(str::getId(start), foundId);
|
||||
break;
|
||||
}
|
||||
default: {
|
||||
@ -882,22 +870,22 @@ ReturnValue_t StarTrackerHandler::interpretDeviceReply(DeviceCommandId_t id,
|
||||
|
||||
switch (id) {
|
||||
case (startracker::REQ_TIME): {
|
||||
result = handleTm(timeSet, startracker::TimeSet::SIZE);
|
||||
result = handleTm(packet, timeSet, startracker::TimeSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::PING_REQUEST): {
|
||||
result = handlePingReply();
|
||||
result = handlePingReply(packet);
|
||||
break;
|
||||
}
|
||||
case (startracker::BOOT):
|
||||
case (startracker::TAKE_IMAGE):
|
||||
break;
|
||||
case (startracker::CHECKSUM): {
|
||||
result = handleChecksumReply();
|
||||
result = handleChecksumReply(packet);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_VERSION): {
|
||||
result = handleTm(versionSet, startracker::VersionSet::SIZE);
|
||||
result = handleTm(packet, versionSet, startracker::VersionSet::SIZE);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
@ -908,23 +896,23 @@ ReturnValue_t StarTrackerHandler::interpretDeviceReply(DeviceCommandId_t id,
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_INTERFACE): {
|
||||
result = handleTm(interfaceSet, startracker::InterfaceSet::SIZE);
|
||||
result = handleTm(packet, interfaceSet, startracker::InterfaceSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_POWER): {
|
||||
result = handleTm(powerSet, startracker::PowerSet::SIZE);
|
||||
result = handleTm(packet, powerSet, startracker::PowerSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_SOLUTION): {
|
||||
result = handleTm(solutionSet, startracker::SolutionSet::SIZE);
|
||||
result = handleTm(packet, solutionSet, startracker::SolutionSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_TEMPERATURE): {
|
||||
result = handleTm(temperatureSet, startracker::TemperatureSet::SIZE);
|
||||
result = handleTm(packet, temperatureSet, startracker::TemperatureSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_HISTOGRAM): {
|
||||
result = handleTm(histogramSet, startracker::HistogramSet::SIZE);
|
||||
result = handleTm(packet, histogramSet, startracker::HistogramSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::SUBSCRIPTION):
|
||||
@ -941,63 +929,63 @@ ReturnValue_t StarTrackerHandler::interpretDeviceReply(DeviceCommandId_t id,
|
||||
case (startracker::VALIDATION):
|
||||
case (startracker::IMAGE_PROCESSOR):
|
||||
case (startracker::ALGO): {
|
||||
result = handleSetParamReply();
|
||||
result = handleSetParamReply(packet);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_CAMERA): {
|
||||
handleParamRequest(cameraSet, startracker::CameraSet::SIZE);
|
||||
handleParamRequest(packet, cameraSet, startracker::CameraSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_LIMITS): {
|
||||
handleParamRequest(limitsSet, startracker::LimitsSet::SIZE);
|
||||
handleParamRequest(packet, limitsSet, startracker::LimitsSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_LOG_LEVEL): {
|
||||
handleParamRequest(loglevelSet, startracker::LogLevelSet::SIZE);
|
||||
handleParamRequest(packet, loglevelSet, startracker::LogLevelSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_MOUNTING): {
|
||||
handleParamRequest(mountingSet, startracker::MountingSet::SIZE);
|
||||
handleParamRequest(packet, mountingSet, startracker::MountingSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_IMAGE_PROCESSOR): {
|
||||
handleParamRequest(imageProcessorSet, startracker::ImageProcessorSet::SIZE);
|
||||
handleParamRequest(packet, imageProcessorSet, startracker::ImageProcessorSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_CENTROIDING): {
|
||||
handleParamRequest(centroidingSet, startracker::CentroidingSet::SIZE);
|
||||
handleParamRequest(packet, centroidingSet, startracker::CentroidingSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_LISA): {
|
||||
handleParamRequest(lisaSet, startracker::LisaSet::SIZE);
|
||||
handleParamRequest(packet, lisaSet, startracker::LisaSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_MATCHING): {
|
||||
handleParamRequest(matchingSet, startracker::MatchingSet::SIZE);
|
||||
handleParamRequest(packet, matchingSet, startracker::MatchingSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_TRACKING): {
|
||||
handleParamRequest(trackingSet, startracker::TrackingSet::SIZE);
|
||||
handleParamRequest(packet, trackingSet, startracker::TrackingSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_VALIDATION): {
|
||||
handleParamRequest(validationSet, startracker::ValidationSet::SIZE);
|
||||
handleParamRequest(packet, validationSet, startracker::ValidationSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_ALGO): {
|
||||
handleParamRequest(algoSet, startracker::AlgoSet::SIZE);
|
||||
handleParamRequest(packet, algoSet, startracker::AlgoSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_SUBSCRIPTION): {
|
||||
handleParamRequest(subscriptionSet, startracker::SubscriptionSet::SIZE);
|
||||
handleParamRequest(packet, subscriptionSet, startracker::SubscriptionSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_LOG_SUBSCRIPTION): {
|
||||
handleParamRequest(logSubscriptionSet, startracker::LogSubscriptionSet::SIZE);
|
||||
handleParamRequest(packet, logSubscriptionSet, startracker::LogSubscriptionSet::SIZE);
|
||||
break;
|
||||
}
|
||||
case (startracker::REQ_DEBUG_CAMERA): {
|
||||
handleParamRequest(debugCameraSet, startracker::DebugCameraSet::SIZE);
|
||||
handleParamRequest(packet, debugCameraSet, startracker::DebugCameraSet::SIZE);
|
||||
break;
|
||||
}
|
||||
default: {
|
||||
@ -1328,9 +1316,8 @@ ReturnValue_t StarTrackerHandler::checkMode(ActionId_t actionId) {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::scanForActionReply(DeviceCommandId_t* foundId) {
|
||||
const uint8_t* reply = dataLinkLayer.getReply();
|
||||
switch (*reply) {
|
||||
ReturnValue_t StarTrackerHandler::scanForActionReply(uint8_t replyId, DeviceCommandId_t* foundId) {
|
||||
switch (replyId) {
|
||||
case (startracker::ID::PING): {
|
||||
*foundId = startracker::PING_REQUEST;
|
||||
break;
|
||||
@ -1359,9 +1346,9 @@ ReturnValue_t StarTrackerHandler::scanForActionReply(DeviceCommandId_t* foundId)
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::scanForSetParameterReply(DeviceCommandId_t* foundId) {
|
||||
const uint8_t* reply = dataLinkLayer.getReply();
|
||||
switch (*reply) {
|
||||
ReturnValue_t StarTrackerHandler::scanForSetParameterReply(uint8_t replyId,
|
||||
DeviceCommandId_t* foundId) {
|
||||
switch (replyId) {
|
||||
case (startracker::ID::SUBSCRIPTION): {
|
||||
*foundId = startracker::SUBSCRIPTION;
|
||||
break;
|
||||
@ -1426,9 +1413,9 @@ ReturnValue_t StarTrackerHandler::scanForSetParameterReply(DeviceCommandId_t* fo
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::scanForGetParameterReply(DeviceCommandId_t* foundId) {
|
||||
const uint8_t* reply = dataLinkLayer.getReply();
|
||||
switch (*reply) {
|
||||
ReturnValue_t StarTrackerHandler::scanForGetParameterReply(uint8_t replyId,
|
||||
DeviceCommandId_t* foundId) {
|
||||
switch (replyId) {
|
||||
case (startracker::ID::CAMERA): {
|
||||
*foundId = startracker::REQ_CAMERA;
|
||||
break;
|
||||
@ -1494,9 +1481,8 @@ ReturnValue_t StarTrackerHandler::scanForGetParameterReply(DeviceCommandId_t* fo
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::scanForTmReply(DeviceCommandId_t* foundId) {
|
||||
const uint8_t* reply = dataLinkLayer.getReply();
|
||||
switch (*reply) {
|
||||
ReturnValue_t StarTrackerHandler::scanForTmReply(uint8_t replyId, DeviceCommandId_t* foundId) {
|
||||
switch (replyId) {
|
||||
case (startracker::ID::VERSION): {
|
||||
*foundId = startracker::REQ_VERSION;
|
||||
break;
|
||||
@ -1527,7 +1513,7 @@ ReturnValue_t StarTrackerHandler::scanForTmReply(DeviceCommandId_t* foundId) {
|
||||
}
|
||||
default: {
|
||||
sif::debug << "StarTrackerHandler::scanForTmReply: Reply contains invalid reply id: "
|
||||
<< static_cast<unsigned int>(*reply) << std::endl;
|
||||
<< static_cast<unsigned int>(replyId) << std::endl;
|
||||
return returnvalue::FAILED;
|
||||
break;
|
||||
}
|
||||
@ -1538,7 +1524,7 @@ ReturnValue_t StarTrackerHandler::scanForTmReply(DeviceCommandId_t* foundId) {
|
||||
void StarTrackerHandler::handleEvent(EventMessage* eventMessage) {
|
||||
object_id_t objectId = eventMessage->getReporter();
|
||||
switch (objectId) {
|
||||
case objects::STR_HELPER: {
|
||||
case objects::STR_COM_IF: {
|
||||
// All events from image loader signal either that the operation was successful or that it
|
||||
// failed
|
||||
strHelperHandlingSpecialRequest = false;
|
||||
@ -1586,9 +1572,8 @@ void StarTrackerHandler::prepareBootCommand() {
|
||||
uint32_t length = 0;
|
||||
struct BootActionRequest bootRequest = {BOOT_REGION_ID};
|
||||
arc_pack_boot_action_req(&bootRequest, commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareChecksumCommand(const uint8_t* commandData,
|
||||
@ -1620,9 +1605,8 @@ ReturnValue_t StarTrackerHandler::prepareChecksumCommand(const uint8_t* commandD
|
||||
}
|
||||
uint32_t rawCmdLength = 0;
|
||||
arc_pack_checksum_action_req(&req, commandBuffer, &rawCmdLength);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, rawCmdLength);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = rawCmdLength;
|
||||
checksumCmd.rememberRegion = req.region;
|
||||
checksumCmd.rememberAddress = req.address;
|
||||
checksumCmd.rememberLength = req.length;
|
||||
@ -1632,51 +1616,45 @@ ReturnValue_t StarTrackerHandler::prepareChecksumCommand(const uint8_t* commandD
|
||||
void StarTrackerHandler::prepareTimeRequest() {
|
||||
uint32_t length = 0;
|
||||
arc_tm_pack_time_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
}
|
||||
|
||||
void StarTrackerHandler::preparePingRequest() {
|
||||
uint32_t length = 0;
|
||||
struct PingActionRequest pingRequest = {PING_ID};
|
||||
arc_pack_ping_action_req(&pingRequest, commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
}
|
||||
|
||||
void StarTrackerHandler::prepareVersionRequest() {
|
||||
uint32_t length = 0;
|
||||
arc_tm_pack_version_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
}
|
||||
|
||||
void StarTrackerHandler::prepareInterfaceRequest() {
|
||||
uint32_t length = 0;
|
||||
arc_tm_pack_interface_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
}
|
||||
|
||||
void StarTrackerHandler::preparePowerRequest() {
|
||||
uint32_t length = 0;
|
||||
arc_tm_pack_power_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
}
|
||||
|
||||
void StarTrackerHandler::prepareSwitchToBootloaderCmd() {
|
||||
uint32_t length = 0;
|
||||
struct RebootActionRequest rebootReq {};
|
||||
arc_pack_reboot_action_req(&rebootReq, commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
}
|
||||
|
||||
void StarTrackerHandler::prepareTakeImageCommand(const uint8_t* commandData) {
|
||||
@ -1684,33 +1662,29 @@ void StarTrackerHandler::prepareTakeImageCommand(const uint8_t* commandData) {
|
||||
struct CameraActionRequest camReq;
|
||||
camReq.actionid = *commandData;
|
||||
arc_pack_camera_action_req(&camReq, commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
}
|
||||
|
||||
void StarTrackerHandler::prepareSolutionRequest() {
|
||||
uint32_t length = 0;
|
||||
arc_tm_pack_solution_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
}
|
||||
|
||||
void StarTrackerHandler::prepareTemperatureRequest() {
|
||||
uint32_t length = 0;
|
||||
arc_tm_pack_temperature_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
}
|
||||
|
||||
void StarTrackerHandler::prepareHistogramRequest() {
|
||||
uint32_t length = 0;
|
||||
arc_tm_pack_histogram_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareParamCommand(const uint8_t* commandData,
|
||||
@ -1721,182 +1695,164 @@ ReturnValue_t StarTrackerHandler::prepareParamCommand(const uint8_t* commandData
|
||||
if (commandDataLen > MAX_PATH_SIZE) {
|
||||
return FILE_PATH_TOO_LONG;
|
||||
}
|
||||
std::string fullName(reinterpret_cast<const char*>(commandData), commandDataLen);
|
||||
|
||||
result = paramSet.create(fullName, commandBuffer);
|
||||
result = paramSet.create(commandBuffer);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
dataLinkLayer.encodeFrame(commandBuffer, paramSet.getSize());
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = paramSet.getSize();
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestCameraParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_camera_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestLimitsParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_limits_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestLogLevelParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_loglevel_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestMountingParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_mounting_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestImageProcessorParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_imageprocessor_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestCentroidingParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_centroiding_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestLisaParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_lisa_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestMatchingParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_matching_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestTrackingParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_tracking_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestValidationParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_validation_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestAlgoParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_algo_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestSubscriptionParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_subscription_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestLogSubscriptionParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_logsubscription_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::prepareRequestDebugCameraParams() {
|
||||
uint32_t length = 0;
|
||||
arc_pack_debugcamera_parameter_req(commandBuffer, &length);
|
||||
dataLinkLayer.encodeFrame(commandBuffer, length);
|
||||
rawPacket = dataLinkLayer.getEncodedFrame();
|
||||
rawPacketLen = dataLinkLayer.getEncodedLength();
|
||||
rawPacket = commandBuffer;
|
||||
rawPacketLen = length;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::handleSetParamReply() {
|
||||
const uint8_t* reply = dataLinkLayer.getReply();
|
||||
uint8_t status = *(reply + STATUS_OFFSET);
|
||||
ReturnValue_t StarTrackerHandler::handleSetParamReply(const uint8_t* rawFrame) {
|
||||
uint8_t status = str::getStatusField(rawFrame);
|
||||
if (status != startracker::STATUS_OK) {
|
||||
sif::warning << "StarTrackerHandler::handleSetParamReply: Failed to execute parameter set "
|
||||
" command with parameter ID"
|
||||
<< static_cast<unsigned int>(*(reply + PARAMETER_ID_OFFSET)) << std::endl;
|
||||
<< static_cast<unsigned int>(*(rawFrame + PARAMETER_ID_OFFSET)) << std::endl;
|
||||
if (internalState != InternalState::IDLE) {
|
||||
internalState = InternalState::IDLE;
|
||||
}
|
||||
return SET_PARAM_FAILED;
|
||||
}
|
||||
if (internalState != InternalState::IDLE) {
|
||||
handleStartup(reply + PARAMETER_ID_OFFSET);
|
||||
handleStartup(*(rawFrame + PARAMETER_ID_OFFSET));
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::handleActionReply() {
|
||||
const uint8_t* reply = dataLinkLayer.getReply();
|
||||
uint8_t status = *(reply + STATUS_OFFSET);
|
||||
ReturnValue_t StarTrackerHandler::handleActionReply(const uint8_t* rawFrame) {
|
||||
uint8_t status = str::getStatusField(rawFrame);
|
||||
if (status != startracker::STATUS_OK) {
|
||||
sif::warning << "StarTrackerHandler::handleActionReply: Failed to execute action "
|
||||
<< "command with action ID "
|
||||
<< static_cast<unsigned int>(*(reply + ACTION_ID_OFFSET)) << " and status "
|
||||
<< static_cast<unsigned int>(*(rawFrame + ACTION_ID_OFFSET)) << " and status "
|
||||
<< static_cast<unsigned int>(status) << std::endl;
|
||||
return ACTION_FAILED;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::handleChecksumReply() {
|
||||
ReturnValue_t StarTrackerHandler::handleChecksumReply(const uint8_t* rawFrame) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
result = handleActionReply();
|
||||
result = handleActionReply(rawFrame);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
const uint8_t* replyData = dataLinkLayer.getReply() + ACTION_DATA_OFFSET;
|
||||
const uint8_t* replyData = rawFrame + ACTION_DATA_OFFSET;
|
||||
startracker::ChecksumReply checksumReply(replyData);
|
||||
if (checksumReply.getRegion() != checksumCmd.rememberRegion) {
|
||||
sif::warning << "StarTrackerHandler::handleChecksumReply: Region mismatch" << std::endl;
|
||||
@ -1919,13 +1875,14 @@ ReturnValue_t StarTrackerHandler::handleChecksumReply() {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::handleParamRequest(LocalPoolDataSetBase& dataset, size_t size) {
|
||||
ReturnValue_t StarTrackerHandler::handleParamRequest(const uint8_t* rawFrame,
|
||||
LocalPoolDataSetBase& dataset, size_t size) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
result = dataset.read(TIMEOUT_TYPE, MUTEX_TIMEOUT);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
const uint8_t* reply = dataLinkLayer.getReply() + PARAMS_OFFSET;
|
||||
const uint8_t* reply = rawFrame + PARAMS_OFFSET;
|
||||
dataset.setValidityBufferGeneration(false);
|
||||
result = dataset.deSerialize(&reply, &size, SerializeIF::Endianness::LITTLE);
|
||||
if (result != returnvalue::OK) {
|
||||
@ -1943,25 +1900,20 @@ ReturnValue_t StarTrackerHandler::handleParamRequest(LocalPoolDataSetBase& datas
|
||||
return result;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::handlePingReply() {
|
||||
ReturnValue_t StarTrackerHandler::handlePingReply(const uint8_t* rawFrame) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint32_t pingId = 0;
|
||||
const uint8_t* reply = dataLinkLayer.getReply();
|
||||
uint8_t status = dataLinkLayer.getStatusField();
|
||||
const uint8_t* buffer = reply + ACTION_DATA_OFFSET;
|
||||
uint8_t status = str::getStatusField(rawFrame);
|
||||
const uint8_t* buffer = rawFrame + ACTION_DATA_OFFSET;
|
||||
size_t size = sizeof(pingId);
|
||||
SerializeAdapter::deSerialize(&pingId, &buffer, &size, SerializeIF::Endianness::LITTLE);
|
||||
#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_STARTRACKER == 1
|
||||
sif::info << "StarTracker: Ping status: " << static_cast<unsigned int>(status) << std::endl;
|
||||
sif::info << "Ping id: 0x" << std::hex << pingId << std::endl;
|
||||
#endif /* OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_STARTRACKER == 1 */
|
||||
sif::info << "Ping ID: 0x" << std::hex << pingId << std::endl;
|
||||
if (status != startracker::STATUS_OK || pingId != PING_ID) {
|
||||
sif::warning << "StarTrackerHandler::handlePingReply: Ping failed" << std::endl;
|
||||
sif::warning << "STR: Ping failed" << std::endl;
|
||||
result = PING_FAILED;
|
||||
} else {
|
||||
#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_STARTRACKER == 1
|
||||
sif::info << "StarTracker: Ping successful" << std::endl;
|
||||
#endif
|
||||
sif::info << "STR: Ping OK" << std::endl;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
@ -2001,9 +1953,10 @@ ReturnValue_t StarTrackerHandler::checkProgram() {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::handleTm(LocalPoolDataSetBase& dataset, size_t size) {
|
||||
ReturnValue_t StarTrackerHandler::handleTm(const uint8_t* rawFrame, LocalPoolDataSetBase& dataset,
|
||||
size_t size) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t status = *(dataLinkLayer.getReply() + STATUS_OFFSET);
|
||||
uint8_t status = str::getStatusField(rawFrame);
|
||||
if (status != startracker::STATUS_OK) {
|
||||
sif::warning << "StarTrackerHandler::handleTm: Reply error: "
|
||||
<< static_cast<unsigned int>(status) << std::endl;
|
||||
@ -2013,7 +1966,7 @@ ReturnValue_t StarTrackerHandler::handleTm(LocalPoolDataSetBase& dataset, size_t
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
const uint8_t* reply = dataLinkLayer.getReply() + TICKS_OFFSET;
|
||||
const uint8_t* reply = rawFrame + TICKS_OFFSET;
|
||||
dataset.setValidityBufferGeneration(false);
|
||||
result = dataset.deSerialize(&reply, &size, SerializeIF::Endianness::LITTLE);
|
||||
if (result != returnvalue::OK) {
|
||||
@ -2031,9 +1984,10 @@ ReturnValue_t StarTrackerHandler::handleTm(LocalPoolDataSetBase& dataset, size_t
|
||||
return result;
|
||||
}
|
||||
|
||||
ReturnValue_t StarTrackerHandler::handleActionReplySet(LocalPoolDataSetBase& dataset, size_t size) {
|
||||
ReturnValue_t StarTrackerHandler::handleActionReplySet(const uint8_t* rawFrame,
|
||||
LocalPoolDataSetBase& dataset, size_t size) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint8_t status = *(dataLinkLayer.getReply() + STATUS_OFFSET);
|
||||
uint8_t status = str::getStatusField(rawFrame);
|
||||
if (status != startracker::STATUS_OK) {
|
||||
sif::warning << "StarTrackerHandler::handleActionReplySet: Reply error: "
|
||||
<< static_cast<unsigned int>(status) << std::endl;
|
||||
@ -2043,7 +1997,7 @@ ReturnValue_t StarTrackerHandler::handleActionReplySet(LocalPoolDataSetBase& dat
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
const uint8_t* reply = dataLinkLayer.getReply() + ACTION_DATA_OFFSET;
|
||||
const uint8_t* reply = rawFrame + ACTION_DATA_OFFSET;
|
||||
dataset.setValidityBufferGeneration(false);
|
||||
result = dataset.deSerialize(&reply, &size, SerializeIF::Endianness::LITTLE);
|
||||
if (result != returnvalue::OK) {
|
||||
@ -2061,8 +2015,8 @@ ReturnValue_t StarTrackerHandler::handleActionReplySet(LocalPoolDataSetBase& dat
|
||||
return result;
|
||||
}
|
||||
|
||||
void StarTrackerHandler::handleStartup(const uint8_t* parameterId) {
|
||||
switch (*parameterId) {
|
||||
void StarTrackerHandler::handleStartup(uint8_t parameterId) {
|
||||
switch (parameterId) {
|
||||
case (startracker::ID::LOG_LEVEL): {
|
||||
bootState = FwBootState::LIMITS;
|
||||
break;
|
||||
@ -2117,8 +2071,8 @@ void StarTrackerHandler::handleStartup(const uint8_t* parameterId) {
|
||||
break;
|
||||
}
|
||||
default: {
|
||||
sif::debug << "StarTrackerHandler::handleStartup: Received parameter reply with unexpected"
|
||||
<< " parameter ID" << std::endl;
|
||||
sif::warning << "StarTrackerHandler::handleStartup: Received parameter reply with unexpected"
|
||||
<< " parameter ID " << (int)parameterId << std::endl;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
@ -2,20 +2,19 @@
|
||||
#define MISSION_DEVICES_STARTRACKERHANDLER_H_
|
||||
|
||||
#include <fsfw/datapool/PoolReadGuard.h>
|
||||
#include <linux/devices/startracker/StarTrackerJsonCommands.h>
|
||||
|
||||
#include <thread>
|
||||
|
||||
#include "ArcsecDatalinkLayer.h"
|
||||
#include "ArcsecJsonParamBase.h"
|
||||
#include "OBSWConfig.h"
|
||||
#include "StrHelper.h"
|
||||
#include "StrComHandler.h"
|
||||
#include "arcsec/common/SLIP.h"
|
||||
#include "devices/powerSwitcherList.h"
|
||||
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
||||
#include "fsfw/src/fsfw/serialize/SerializeAdapter.h"
|
||||
#include "fsfw/timemanager/Countdown.h"
|
||||
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
|
||||
#include "thirdparty/arcsec_star_tracker/common/SLIP.h"
|
||||
#include "strJsonCommands.h"
|
||||
|
||||
/**
|
||||
* @brief This is the device handler for the star tracker from arcsec.
|
||||
@ -38,7 +37,8 @@ class StarTrackerHandler : public DeviceHandlerBase {
|
||||
* to high to enable the device.
|
||||
*/
|
||||
StarTrackerHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie,
|
||||
const char* jsonFileStr, StrHelper* strHelper, power::Switch_t powerSwitch);
|
||||
const char* jsonFileStr, StrComHandler* strHelper,
|
||||
power::Switch_t powerSwitch);
|
||||
virtual ~StarTrackerHandler();
|
||||
|
||||
ReturnValue_t initialize() override;
|
||||
@ -147,14 +147,14 @@ class StarTrackerHandler : public DeviceHandlerBase {
|
||||
static const size_t MAX_PATH_SIZE = 50;
|
||||
static const size_t MAX_FILE_NAME = 30;
|
||||
|
||||
static const uint8_t STATUS_OFFSET = 1;
|
||||
static const uint8_t PARAMS_OFFSET = 1;
|
||||
static const uint8_t TICKS_OFFSET = 2;
|
||||
static const uint8_t TIME_OFFSET = 6;
|
||||
static const uint8_t TM_DATA_FIELD_OFFSET = 14;
|
||||
static const uint8_t PARAMETER_ID_OFFSET = 0;
|
||||
static const uint8_t ACTION_ID_OFFSET = 0;
|
||||
static const uint8_t ACTION_DATA_OFFSET = 2;
|
||||
static const uint8_t STATUS_OFFSET = 2;
|
||||
static const uint8_t PARAMS_OFFSET = 2;
|
||||
static const uint8_t TICKS_OFFSET = 3;
|
||||
static const uint8_t TIME_OFFSET = 7;
|
||||
static const uint8_t PARAMETER_ID_OFFSET = 1;
|
||||
static const uint8_t ACTION_ID_OFFSET = 1;
|
||||
static const uint8_t ACTION_DATA_OFFSET = 3;
|
||||
|
||||
// Ping request will reply ping with this ID (data field)
|
||||
static const uint32_t PING_ID = 0x55;
|
||||
static const uint32_t BOOT_REGION_ID = 1;
|
||||
@ -182,8 +182,6 @@ class StarTrackerHandler : public DeviceHandlerBase {
|
||||
|
||||
MessageQueueIF* eventQueue = nullptr;
|
||||
|
||||
ArcsecDatalinkLayer dataLinkLayer;
|
||||
|
||||
startracker::TemperatureSet temperatureSet;
|
||||
startracker::VersionSet versionSet;
|
||||
startracker::PowerSet powerSet;
|
||||
@ -208,7 +206,7 @@ class StarTrackerHandler : public DeviceHandlerBase {
|
||||
startracker::DebugCameraSet debugCameraSet;
|
||||
|
||||
// Pointer to object responsible for uploading and downloading images to/from the star tracker
|
||||
StrHelper* strHelper = nullptr;
|
||||
StrComHandler* strHelper = nullptr;
|
||||
|
||||
uint8_t commandBuffer[startracker::MAX_FRAME_SIZE];
|
||||
|
||||
@ -310,10 +308,10 @@ class StarTrackerHandler : public DeviceHandlerBase {
|
||||
*/
|
||||
void slipInit();
|
||||
|
||||
ReturnValue_t scanForActionReply(DeviceCommandId_t* foundId);
|
||||
ReturnValue_t scanForSetParameterReply(DeviceCommandId_t* foundId);
|
||||
ReturnValue_t scanForGetParameterReply(DeviceCommandId_t* foundId);
|
||||
ReturnValue_t scanForTmReply(DeviceCommandId_t* foundId);
|
||||
ReturnValue_t scanForActionReply(uint8_t replyId, DeviceCommandId_t* foundId);
|
||||
ReturnValue_t scanForSetParameterReply(uint8_t replyId, DeviceCommandId_t* foundId);
|
||||
ReturnValue_t scanForGetParameterReply(uint8_t replyId, DeviceCommandId_t* foundId);
|
||||
ReturnValue_t scanForTmReply(uint8_t replyId, DeviceCommandId_t* foundId);
|
||||
|
||||
/**
|
||||
* @brief Fills command buffer with data to ping the star tracker
|
||||
@ -435,12 +433,13 @@ class StarTrackerHandler : public DeviceHandlerBase {
|
||||
/**
|
||||
* @brief Handles action replies with datasets.
|
||||
*/
|
||||
ReturnValue_t handleActionReplySet(LocalPoolDataSetBase& dataset, size_t size);
|
||||
ReturnValue_t handleActionReplySet(const uint8_t* rawFrame, LocalPoolDataSetBase& dataset,
|
||||
size_t size);
|
||||
|
||||
/**
|
||||
* @brief Default function to handle action replies
|
||||
*/
|
||||
ReturnValue_t handleActionReply();
|
||||
ReturnValue_t handleActionReply(const uint8_t* rawFrame);
|
||||
|
||||
/**
|
||||
* @brief Handles reply to upload centroid command
|
||||
@ -450,16 +449,17 @@ class StarTrackerHandler : public DeviceHandlerBase {
|
||||
/**
|
||||
* @brief Handles reply to checksum command
|
||||
*/
|
||||
ReturnValue_t handleChecksumReply();
|
||||
ReturnValue_t handleChecksumReply(const uint8_t* rawFrame);
|
||||
|
||||
/**
|
||||
* @brief Handles all set parameter replies
|
||||
*/
|
||||
ReturnValue_t handleSetParamReply();
|
||||
ReturnValue_t handleSetParamReply(const uint8_t* rawFrame);
|
||||
|
||||
ReturnValue_t handlePingReply();
|
||||
ReturnValue_t handlePingReply(const uint8_t* rawFrame);
|
||||
|
||||
ReturnValue_t handleParamRequest(LocalPoolDataSetBase& dataset, size_t size);
|
||||
ReturnValue_t handleParamRequest(const uint8_t* rawFrame, LocalPoolDataSetBase& dataset,
|
||||
size_t size);
|
||||
|
||||
/**
|
||||
* @brief Checks the loaded program by means of the version set
|
||||
@ -469,7 +469,7 @@ class StarTrackerHandler : public DeviceHandlerBase {
|
||||
/**
|
||||
* @brief Handles the startup state machine
|
||||
*/
|
||||
void handleStartup(const uint8_t* parameterId);
|
||||
void handleStartup(uint8_t parameterId);
|
||||
|
||||
/**
|
||||
* @brief Handles telemtry replies and fills the appropriate dataset
|
||||
@ -479,7 +479,7 @@ class StarTrackerHandler : public DeviceHandlerBase {
|
||||
*
|
||||
* @return returnvalue::OK if successful, otherwise error return value
|
||||
*/
|
||||
ReturnValue_t handleTm(LocalPoolDataSetBase& dataset, size_t size);
|
||||
ReturnValue_t handleTm(const uint8_t* rawFrame, LocalPoolDataSetBase& dataset, size_t size);
|
||||
|
||||
/**
|
||||
* @brief Checks if star tracker is in valid mode for executing the received command.
|
||||
|
@ -1,6 +1,9 @@
|
||||
#include "StrHelper.h"
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <fsfw/filesystem/HasFileSystemIF.h>
|
||||
#include <fsfw/tasks/TaskFactory.h>
|
||||
#include <fsfw/timemanager/Stopwatch.h>
|
||||
#include <linux/devices/startracker/StrComHandler.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <filesystem>
|
||||
#include <fstream>
|
||||
@ -8,16 +11,22 @@
|
||||
#include "OBSWConfig.h"
|
||||
#include "eive/definitions.h"
|
||||
#include "fsfw/timemanager/Countdown.h"
|
||||
#include "helpers.h"
|
||||
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
|
||||
#include "mission/utility/Filenaming.h"
|
||||
#include "mission/utility/ProgressPrinter.h"
|
||||
#include "mission/utility/Timestamp.h"
|
||||
|
||||
StrHelper::StrHelper(object_id_t objectId) : SystemObject(objectId) {}
|
||||
using namespace returnvalue;
|
||||
|
||||
StrHelper::~StrHelper() {}
|
||||
StrComHandler::StrComHandler(object_id_t objectId) : SystemObject(objectId) {
|
||||
lock = MutexFactory::instance()->createMutex();
|
||||
semaphore.acquire();
|
||||
}
|
||||
|
||||
ReturnValue_t StrHelper::initialize() {
|
||||
StrComHandler::~StrComHandler() {}
|
||||
|
||||
ReturnValue_t StrComHandler::initialize() {
|
||||
#ifdef XIPHOS_Q7S
|
||||
sdcMan = SdCardManager::instance();
|
||||
if (sdcMan == nullptr) {
|
||||
@ -28,53 +37,63 @@ ReturnValue_t StrHelper::initialize() {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StrHelper::performOperation(uint8_t operationCode) {
|
||||
ReturnValue_t StrComHandler::performOperation(uint8_t operationCode) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
semaphore.acquire();
|
||||
while (true) {
|
||||
switch (internalState) {
|
||||
case InternalState::IDLE: {
|
||||
semaphore.acquire();
|
||||
lock->lockMutex();
|
||||
state = InternalState::SLEEPING;
|
||||
datalinkLayer.reset();
|
||||
lock->unlockMutex();
|
||||
semaphore.acquire();
|
||||
switch (state) {
|
||||
case InternalState::POLL_ONE_REPLY: {
|
||||
// Stopwatch watch;
|
||||
replyTimeout.setTimeout(200);
|
||||
replyResult = readOneReply(static_cast<uint32_t>(state));
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
replyWasReceived = true;
|
||||
}
|
||||
break;
|
||||
}
|
||||
case InternalState::UPLOAD_IMAGE: {
|
||||
replyTimeout.setTimeout(200);
|
||||
result = performImageUpload();
|
||||
if (result == returnvalue::OK) {
|
||||
triggerEvent(IMAGE_UPLOAD_SUCCESSFUL);
|
||||
} else {
|
||||
triggerEvent(IMAGE_UPLOAD_FAILED);
|
||||
}
|
||||
internalState = InternalState::IDLE;
|
||||
break;
|
||||
}
|
||||
case InternalState::DOWNLOAD_IMAGE: {
|
||||
replyTimeout.setTimeout(200);
|
||||
result = performImageDownload();
|
||||
if (result == returnvalue::OK) {
|
||||
triggerEvent(IMAGE_DOWNLOAD_SUCCESSFUL);
|
||||
} else {
|
||||
triggerEvent(IMAGE_DOWNLOAD_FAILED);
|
||||
}
|
||||
internalState = InternalState::IDLE;
|
||||
break;
|
||||
}
|
||||
case InternalState::FLASH_READ: {
|
||||
replyTimeout.setTimeout(200);
|
||||
result = performFlashRead();
|
||||
if (result == returnvalue::OK) {
|
||||
triggerEvent(FLASH_READ_SUCCESSFUL);
|
||||
} else {
|
||||
triggerEvent(FLASH_READ_FAILED);
|
||||
}
|
||||
internalState = InternalState::IDLE;
|
||||
break;
|
||||
}
|
||||
case InternalState::FIRMWARE_UPDATE: {
|
||||
replyTimeout.setTimeout(200);
|
||||
result = performFirmwareUpdate();
|
||||
if (result == returnvalue::OK) {
|
||||
triggerEvent(FIRMWARE_UPDATE_SUCCESSFUL);
|
||||
} else {
|
||||
triggerEvent(FIRMWARE_UPDATE_FAILED);
|
||||
}
|
||||
internalState = InternalState::IDLE;
|
||||
break;
|
||||
}
|
||||
default:
|
||||
@ -84,18 +103,13 @@ ReturnValue_t StrHelper::performOperation(uint8_t operationCode) {
|
||||
}
|
||||
}
|
||||
|
||||
ReturnValue_t StrHelper::setComIF(DeviceCommunicationIF* communicationInterface_) {
|
||||
uartComIF = dynamic_cast<SerialComIF*>(communicationInterface_);
|
||||
if (uartComIF == nullptr) {
|
||||
sif::warning << "StrHelper::initialize: Invalid uart com if" << std::endl;
|
||||
return returnvalue::FAILED;
|
||||
ReturnValue_t StrComHandler::startImageUpload(std::string fullname) {
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
if (state != InternalState::SLEEPING) {
|
||||
return BUSY;
|
||||
}
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void StrHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; }
|
||||
|
||||
ReturnValue_t StrHelper::startImageUpload(std::string fullname) {
|
||||
#ifdef XIPHOS_Q7S
|
||||
ReturnValue_t result = checkPath(fullname);
|
||||
if (result != returnvalue::OK) {
|
||||
@ -106,13 +120,22 @@ ReturnValue_t StrHelper::startImageUpload(std::string fullname) {
|
||||
if (not std::filesystem::exists(fullname)) {
|
||||
return FILE_NOT_EXISTS;
|
||||
}
|
||||
internalState = InternalState::UPLOAD_IMAGE;
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
state = InternalState::UPLOAD_IMAGE;
|
||||
}
|
||||
semaphore.release();
|
||||
terminate = false;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StrHelper::startImageDownload(std::string path) {
|
||||
ReturnValue_t StrComHandler::startImageDownload(std::string path) {
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
if (state != InternalState::SLEEPING) {
|
||||
return BUSY;
|
||||
}
|
||||
}
|
||||
#ifdef XIPHOS_Q7S
|
||||
ReturnValue_t result = checkPath(path);
|
||||
if (result != returnvalue::OK) {
|
||||
@ -123,19 +146,30 @@ ReturnValue_t StrHelper::startImageDownload(std::string path) {
|
||||
return PATH_NOT_EXISTS;
|
||||
}
|
||||
downloadImage.path = path;
|
||||
internalState = InternalState::DOWNLOAD_IMAGE;
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
state = InternalState::DOWNLOAD_IMAGE;
|
||||
}
|
||||
terminate = false;
|
||||
semaphore.release();
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void StrHelper::stopProcess() { terminate = true; }
|
||||
void StrComHandler::stopProcess() { terminate = true; }
|
||||
|
||||
void StrHelper::setDownloadImageName(std::string filename) { downloadImage.filename = filename; }
|
||||
void StrComHandler::setDownloadImageName(std::string filename) {
|
||||
downloadImage.filename = filename;
|
||||
}
|
||||
|
||||
void StrHelper::setFlashReadFilename(std::string filename) { flashRead.filename = filename; }
|
||||
void StrComHandler::setFlashReadFilename(std::string filename) { flashRead.filename = filename; }
|
||||
|
||||
ReturnValue_t StrHelper::startFirmwareUpdate(std::string fullname) {
|
||||
ReturnValue_t StrComHandler::startFirmwareUpdate(std::string fullname) {
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
if (state != InternalState::SLEEPING) {
|
||||
return BUSY;
|
||||
}
|
||||
}
|
||||
#ifdef XIPHOS_Q7S
|
||||
ReturnValue_t result = checkPath(fullname);
|
||||
if (result != returnvalue::OK) {
|
||||
@ -148,13 +182,23 @@ ReturnValue_t StrHelper::startFirmwareUpdate(std::string fullname) {
|
||||
}
|
||||
flashWrite.firstRegion = static_cast<uint8_t>(startracker::FirmwareRegions::FIRST);
|
||||
flashWrite.lastRegion = static_cast<uint8_t>(startracker::FirmwareRegions::LAST);
|
||||
internalState = InternalState::FIRMWARE_UPDATE;
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
state = InternalState::FIRMWARE_UPDATE;
|
||||
}
|
||||
semaphore.release();
|
||||
terminate = false;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StrHelper::startFlashRead(std::string path, uint8_t startRegion, uint32_t length) {
|
||||
ReturnValue_t StrComHandler::startFlashRead(std::string path, uint8_t startRegion,
|
||||
uint32_t length) {
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
if (state != InternalState::SLEEPING) {
|
||||
return BUSY;
|
||||
}
|
||||
}
|
||||
#ifdef XIPHOS_Q7S
|
||||
ReturnValue_t result = checkPath(path);
|
||||
if (result != returnvalue::OK) {
|
||||
@ -167,17 +211,20 @@ ReturnValue_t StrHelper::startFlashRead(std::string path, uint8_t startRegion, u
|
||||
}
|
||||
flashRead.startRegion = startRegion;
|
||||
flashRead.size = length;
|
||||
internalState = InternalState::FLASH_READ;
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
state = InternalState::FLASH_READ;
|
||||
}
|
||||
semaphore.release();
|
||||
terminate = false;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void StrHelper::disableTimestamping() { timestamping = false; }
|
||||
void StrComHandler::disableTimestamping() { timestamping = false; }
|
||||
|
||||
void StrHelper::enableTimestamping() { timestamping = true; }
|
||||
void StrComHandler::enableTimestamping() { timestamping = true; }
|
||||
|
||||
ReturnValue_t StrHelper::performImageDownload() {
|
||||
ReturnValue_t StrComHandler::performImageDownload() {
|
||||
#ifdef XIPHOS_Q7S
|
||||
if (not sdcMan->getActiveSdCard()) {
|
||||
return HasFileSystemIF::FILESYSTEM_INACTIVE;
|
||||
@ -190,6 +237,7 @@ ReturnValue_t StrHelper::performImageDownload() {
|
||||
struct DownloadActionRequest downloadReq;
|
||||
uint32_t size = 0;
|
||||
uint32_t retries = 0;
|
||||
size_t replySize = 0;
|
||||
std::string image = Filenaming::generateAbsoluteFilename(downloadImage.path,
|
||||
downloadImage.filename, timestamping);
|
||||
std::ofstream file(image, std::ios_base::out);
|
||||
@ -202,21 +250,21 @@ ReturnValue_t StrHelper::performImageDownload() {
|
||||
file.close();
|
||||
return returnvalue::OK;
|
||||
}
|
||||
arc_pack_download_action_req(&downloadReq, commandBuffer, &size);
|
||||
arc_pack_download_action_req(&downloadReq, cmdBuf.data(), &size);
|
||||
result = sendAndRead(size, downloadReq.position);
|
||||
if (result != returnvalue::OK) {
|
||||
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
|
||||
uartComIF->flushUartRxBuffer(comCookie);
|
||||
serial::flushRxBuf(serialPort);
|
||||
retries++;
|
||||
continue;
|
||||
}
|
||||
file.close();
|
||||
return result;
|
||||
}
|
||||
result = checkActionReply();
|
||||
result = checkActionReply(replySize);
|
||||
if (result != returnvalue::OK) {
|
||||
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
|
||||
uartComIF->flushUartRxBuffer(comCookie);
|
||||
serial::flushRxBuf(serialPort);
|
||||
retries++;
|
||||
continue;
|
||||
}
|
||||
@ -226,15 +274,14 @@ ReturnValue_t StrHelper::performImageDownload() {
|
||||
result = checkReplyPosition(downloadReq.position);
|
||||
if (result != returnvalue::OK) {
|
||||
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
|
||||
uartComIF->flushUartRxBuffer(comCookie);
|
||||
serial::flushRxBuf(serialPort);
|
||||
retries++;
|
||||
continue;
|
||||
}
|
||||
file.close();
|
||||
return result;
|
||||
}
|
||||
file.write(reinterpret_cast<const char*>(datalinkLayer.getReply() + IMAGE_DATA_OFFSET),
|
||||
CHUNK_SIZE);
|
||||
file.write(reinterpret_cast<const char*>(replyPtr + IMAGE_DATA_OFFSET), CHUNK_SIZE);
|
||||
#if OBSW_DEBUG_STARTRACKER == 1
|
||||
progressPrinter.print(downloadReq.position);
|
||||
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
|
||||
@ -245,7 +292,7 @@ ReturnValue_t StrHelper::performImageDownload() {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StrHelper::performImageUpload() {
|
||||
ReturnValue_t StrComHandler::performImageUpload() {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
uint32_t size = 0;
|
||||
uint32_t imageSize = 0;
|
||||
@ -258,8 +305,7 @@ ReturnValue_t StrHelper::performImageUpload() {
|
||||
#endif
|
||||
std::memset(&uploadReq.data, 0, sizeof(uploadReq.data));
|
||||
if (not std::filesystem::exists(uploadImage.uploadFile)) {
|
||||
triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast<uint32_t>(internalState));
|
||||
internalState = InternalState::IDLE;
|
||||
triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast<uint32_t>(state));
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
std::ifstream file(uploadImage.uploadFile, std::ifstream::binary);
|
||||
@ -276,26 +322,29 @@ ReturnValue_t StrHelper::performImageUpload() {
|
||||
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
|
||||
while ((uploadReq.position + 1) * SIZE_IMAGE_PART < imageSize) {
|
||||
if (terminate) {
|
||||
file.close();
|
||||
return returnvalue::OK;
|
||||
}
|
||||
file.seekg(uploadReq.position * SIZE_IMAGE_PART, file.beg);
|
||||
file.read(reinterpret_cast<char*>(uploadReq.data), SIZE_IMAGE_PART);
|
||||
arc_pack_upload_action_req(&uploadReq, commandBuffer, &size);
|
||||
arc_pack_upload_action_req(&uploadReq, cmdBuf.data(), &size);
|
||||
result = sendAndRead(size, uploadReq.position);
|
||||
if (result != returnvalue::OK) {
|
||||
file.close();
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
result = checkActionReply();
|
||||
result = checkActionReply(replyLen);
|
||||
if (result != returnvalue::OK) {
|
||||
file.close();
|
||||
return result;
|
||||
}
|
||||
#if OBSW_DEBUG_STARTRACKER == 1
|
||||
progressPrinter.print((uploadReq.position + 1) * SIZE_IMAGE_PART);
|
||||
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
|
||||
uploadReq.position++;
|
||||
|
||||
// This does a bit of delaying roughly every second
|
||||
if (uploadReq.position % 50 == 0) {
|
||||
// Some grace time for other tasks
|
||||
TaskFactory::delayTask(2);
|
||||
}
|
||||
}
|
||||
std::memset(uploadReq.data, 0, sizeof(uploadReq.data));
|
||||
uint32_t remainder = imageSize - uploadReq.position * SIZE_IMAGE_PART;
|
||||
@ -303,12 +352,12 @@ ReturnValue_t StrHelper::performImageUpload() {
|
||||
file.read(reinterpret_cast<char*>(uploadReq.data), remainder);
|
||||
file.close();
|
||||
uploadReq.position++;
|
||||
arc_pack_upload_action_req(&uploadReq, commandBuffer, &size);
|
||||
arc_pack_upload_action_req(&uploadReq, cmdBuf.data(), &size);
|
||||
result = sendAndRead(size, uploadReq.position);
|
||||
if (result != returnvalue::OK) {
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
result = checkActionReply();
|
||||
result = checkActionReply(replyLen);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
@ -318,7 +367,7 @@ ReturnValue_t StrHelper::performImageUpload() {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StrHelper::performFirmwareUpdate() {
|
||||
ReturnValue_t StrComHandler::performFirmwareUpdate() {
|
||||
using namespace startracker;
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
result = unlockAndEraseRegions(static_cast<uint32_t>(startracker::FirmwareRegions::FIRST),
|
||||
@ -330,7 +379,7 @@ ReturnValue_t StrHelper::performFirmwareUpdate() {
|
||||
return result;
|
||||
}
|
||||
|
||||
ReturnValue_t StrHelper::performFlashWrite() {
|
||||
ReturnValue_t StrComHandler::performFlashWrite() {
|
||||
#ifdef XIPHOS_Q7S
|
||||
if (not sdcMan->getActiveSdCard()) {
|
||||
return HasFileSystemIF::FILESYSTEM_INACTIVE;
|
||||
@ -340,13 +389,16 @@ ReturnValue_t StrHelper::performFlashWrite() {
|
||||
uint32_t size = 0;
|
||||
uint32_t bytesWritten = 0;
|
||||
uint32_t fileSize = 0;
|
||||
|
||||
struct WriteActionRequest req;
|
||||
if (not std::filesystem::exists(flashWrite.fullname)) {
|
||||
triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast<uint32_t>(internalState));
|
||||
internalState = InternalState::IDLE;
|
||||
triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast<uint32_t>(state));
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
std::ifstream file(flashWrite.fullname, std::ifstream::binary);
|
||||
if (file.bad()) {
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
file.seekg(0, file.end);
|
||||
fileSize = file.tellg();
|
||||
if (fileSize > FLASH_REGION_SIZE * (flashWrite.lastRegion - flashWrite.firstRegion)) {
|
||||
@ -362,7 +414,6 @@ ReturnValue_t StrHelper::performFlashWrite() {
|
||||
req.length = CHUNK_SIZE;
|
||||
for (uint32_t idx = 0; idx < fileChunks; idx++) {
|
||||
if (terminate) {
|
||||
file.close();
|
||||
return returnvalue::OK;
|
||||
}
|
||||
file.seekg(idx * CHUNK_SIZE, file.beg);
|
||||
@ -372,21 +423,23 @@ ReturnValue_t StrHelper::performFlashWrite() {
|
||||
bytesWritten = 0;
|
||||
}
|
||||
req.address = bytesWritten;
|
||||
arc_pack_write_action_req(&req, commandBuffer, &size);
|
||||
arc_pack_write_action_req(&req, cmdBuf.data(), &size);
|
||||
result = sendAndRead(size, req.address);
|
||||
if (result != returnvalue::OK) {
|
||||
file.close();
|
||||
return result;
|
||||
}
|
||||
result = checkActionReply();
|
||||
result = checkActionReply(replyLen);
|
||||
if (result != returnvalue::OK) {
|
||||
file.close();
|
||||
return result;
|
||||
}
|
||||
bytesWritten += CHUNK_SIZE;
|
||||
#if OBSW_DEBUG_STARTRACKER == 1
|
||||
progressPrinter.print(idx * CHUNK_SIZE);
|
||||
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
|
||||
if (idx % 50 == 0) {
|
||||
// Some grace time for other tasks
|
||||
TaskFactory::delayTask(2);
|
||||
}
|
||||
}
|
||||
uint32_t remainingBytes = fileSize - fileChunks * CHUNK_SIZE;
|
||||
file.seekg((fileChunks - 1) * CHUNK_SIZE, file.beg);
|
||||
@ -399,12 +452,12 @@ ReturnValue_t StrHelper::performFlashWrite() {
|
||||
req.address = bytesWritten;
|
||||
req.length = remainingBytes;
|
||||
bytesWritten += remainingBytes;
|
||||
arc_pack_write_action_req(&req, commandBuffer, &size);
|
||||
arc_pack_write_action_req(&req, cmdBuf.data(), &size);
|
||||
result = sendAndRead(size, req.address);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
result = checkActionReply();
|
||||
result = checkActionReply(replyLen);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
@ -414,7 +467,7 @@ ReturnValue_t StrHelper::performFlashWrite() {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StrHelper::performFlashRead() {
|
||||
ReturnValue_t StrComHandler::performFlashRead() {
|
||||
#ifdef XIPHOS_Q7S
|
||||
if (not sdcMan->getActiveSdCard()) {
|
||||
return HasFileSystemIF::FILESYSTEM_INACTIVE;
|
||||
@ -446,29 +499,28 @@ ReturnValue_t StrHelper::performFlashRead() {
|
||||
} else {
|
||||
req.length = CHUNK_SIZE;
|
||||
}
|
||||
arc_pack_read_action_req(&req, commandBuffer, &size);
|
||||
arc_pack_read_action_req(&req, cmdBuf.data(), &size);
|
||||
result = sendAndRead(size, req.address);
|
||||
if (result != returnvalue::OK) {
|
||||
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
|
||||
uartComIF->flushUartRxBuffer(comCookie);
|
||||
serial::flushRxBuf(serialPort);
|
||||
retries++;
|
||||
continue;
|
||||
}
|
||||
file.close();
|
||||
return result;
|
||||
}
|
||||
result = checkActionReply();
|
||||
result = checkActionReply(replyLen);
|
||||
if (result != returnvalue::OK) {
|
||||
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
|
||||
uartComIF->flushUartRxBuffer(comCookie);
|
||||
serial::flushRxBuf(serialPort);
|
||||
retries++;
|
||||
continue;
|
||||
}
|
||||
file.close();
|
||||
return result;
|
||||
}
|
||||
file.write(reinterpret_cast<const char*>(datalinkLayer.getReply() + FLASH_READ_DATA_OFFSET),
|
||||
req.length);
|
||||
file.write(reinterpret_cast<const char*>(replyPtr + FLASH_READ_DATA_OFFSET), req.length);
|
||||
bytesRead += req.length;
|
||||
req.address += req.length;
|
||||
if (req.address >= FLASH_REGION_SIZE) {
|
||||
@ -484,70 +536,29 @@ ReturnValue_t StrHelper::performFlashRead() {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StrHelper::sendAndRead(size_t size, uint32_t parameter, uint32_t delayMs) {
|
||||
ReturnValue_t StrComHandler::sendAndRead(size_t size, uint32_t failParameter) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
ReturnValue_t decResult = returnvalue::OK;
|
||||
size_t receivedDataLen = 0;
|
||||
uint8_t* receivedData = nullptr;
|
||||
size_t bytesLeft = 0;
|
||||
uint32_t missedReplies = 0;
|
||||
datalinkLayer.encodeFrame(commandBuffer, size);
|
||||
result = uartComIF->sendMessage(comCookie, datalinkLayer.getEncodedFrame(),
|
||||
datalinkLayer.getEncodedLength());
|
||||
if (result != returnvalue::OK) {
|
||||
|
||||
const uint8_t* sendData;
|
||||
size_t txFrameLen = 0;
|
||||
datalinkLayer.encodeFrame(cmdBuf.data(), size, &sendData, txFrameLen);
|
||||
int writeResult = write(serialPort, sendData, txFrameLen);
|
||||
if (writeResult < 0) {
|
||||
sif::warning << "StrHelper::sendAndRead: Failed to send packet" << std::endl;
|
||||
triggerEvent(STR_HELPER_SENDING_PACKET_FAILED, result, parameter);
|
||||
triggerEvent(STR_HELPER_SENDING_PACKET_FAILED, result, failParameter);
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
decResult = ArcsecDatalinkLayer::DEC_IN_PROGRESS;
|
||||
while (decResult == ArcsecDatalinkLayer::DEC_IN_PROGRESS) {
|
||||
Countdown delay(delayMs);
|
||||
delay.resetTimer();
|
||||
while (delay.isBusy()) {
|
||||
}
|
||||
result = uartComIF->requestReceiveMessage(comCookie, startracker::MAX_FRAME_SIZE * 2 + 2);
|
||||
if (result != returnvalue::OK) {
|
||||
sif::warning << "StrHelper::sendAndRead: Failed to request reply" << std::endl;
|
||||
triggerEvent(STR_HELPER_REQUESTING_MSG_FAILED, result, parameter);
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
result = uartComIF->readReceivedMessage(comCookie, &receivedData, &receivedDataLen);
|
||||
if (result != returnvalue::OK) {
|
||||
sif::warning << "StrHelper::sendAndRead: Failed to read received message" << std::endl;
|
||||
triggerEvent(STR_HELPER_READING_REPLY_FAILED, result, parameter);
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
if (receivedDataLen == 0 && missedReplies < MAX_POLLS) {
|
||||
missedReplies++;
|
||||
continue;
|
||||
} else if ((receivedDataLen == 0) && (missedReplies >= MAX_POLLS)) {
|
||||
triggerEvent(STR_HELPER_NO_REPLY, parameter);
|
||||
return returnvalue::FAILED;
|
||||
} else {
|
||||
missedReplies = 0;
|
||||
}
|
||||
decResult = datalinkLayer.decodeFrame(receivedData, receivedDataLen, &bytesLeft);
|
||||
if (bytesLeft != 0) {
|
||||
// This should never happen
|
||||
sif::warning << "StrHelper::sendAndRead: Bytes left after decoding" << std::endl;
|
||||
triggerEvent(STR_HELPER_COM_ERROR, result, parameter);
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
}
|
||||
if (decResult != returnvalue::OK) {
|
||||
triggerEvent(STR_HELPER_DEC_ERROR, decResult, parameter);
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
|
||||
return readOneReply(failParameter);
|
||||
}
|
||||
|
||||
ReturnValue_t StrHelper::checkActionReply() {
|
||||
uint8_t type = datalinkLayer.getReplyFrameType();
|
||||
ReturnValue_t StrComHandler::checkActionReply(size_t replySize) {
|
||||
uint8_t type = str::getReplyFrameType(replyPtr);
|
||||
if (type != TMTC_ACTIONREPLY) {
|
||||
sif::warning << "StrHelper::checkActionReply: Received reply with invalid type ID" << std::endl;
|
||||
return INVALID_TYPE_ID;
|
||||
}
|
||||
uint8_t status = datalinkLayer.getStatusField();
|
||||
uint8_t status = str::getStatusField(replyPtr);
|
||||
if (status != ArcsecDatalinkLayer::STATUS_OK) {
|
||||
sif::warning << "StrHelper::checkActionReply: Status failure: "
|
||||
<< static_cast<unsigned int>(status) << std::endl;
|
||||
@ -556,9 +567,9 @@ ReturnValue_t StrHelper::checkActionReply() {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StrHelper::checkReplyPosition(uint32_t expectedPosition) {
|
||||
ReturnValue_t StrComHandler::checkReplyPosition(uint32_t expectedPosition) {
|
||||
uint32_t receivedPosition = 0;
|
||||
std::memcpy(&receivedPosition, datalinkLayer.getReply() + POS_OFFSET, sizeof(receivedPosition));
|
||||
std::memcpy(&receivedPosition, replyPtr + POS_OFFSET, sizeof(receivedPosition));
|
||||
if (receivedPosition != expectedPosition) {
|
||||
triggerEvent(POSITION_MISMATCH, receivedPosition);
|
||||
return returnvalue::FAILED;
|
||||
@ -567,7 +578,7 @@ ReturnValue_t StrHelper::checkReplyPosition(uint32_t expectedPosition) {
|
||||
}
|
||||
|
||||
#ifdef XIPHOS_Q7S
|
||||
ReturnValue_t StrHelper::checkPath(std::string name) {
|
||||
ReturnValue_t StrComHandler::checkPath(std::string name) {
|
||||
if (name.substr(0, sizeof(config::SD_0_MOUNT_POINT)) == std::string(config::SD_0_MOUNT_POINT)) {
|
||||
if (!sdcMan->isSdCardUsable(sd::SLOT_0)) {
|
||||
sif::warning << "StrHelper::checkPath: SD card 0 not mounted" << std::endl;
|
||||
@ -584,7 +595,112 @@ ReturnValue_t StrHelper::checkPath(std::string name) {
|
||||
}
|
||||
#endif
|
||||
|
||||
ReturnValue_t StrHelper::unlockAndEraseRegions(uint32_t from, uint32_t to) {
|
||||
ReturnValue_t StrComHandler::initializeInterface(CookieIF* cookie) {
|
||||
if (cookie == nullptr) {
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
SerialCookie* serCookie = dynamic_cast<SerialCookie*>(cookie);
|
||||
if (serCookie == nullptr) {
|
||||
return DeviceCommunicationIF::INVALID_COOKIE_TYPE;
|
||||
}
|
||||
// comCookie = serCookie;
|
||||
std::string devname = serCookie->getDeviceFile();
|
||||
/* Get file descriptor */
|
||||
serialPort = open(devname.c_str(), O_RDWR);
|
||||
if (serialPort < 0) {
|
||||
sif::warning << "StrComHandler: open call failed with error [" << errno << ", "
|
||||
<< strerror(errno) << std::endl;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
// Setting up UART parameters
|
||||
tty.c_cflag &= ~PARENB; // Clear parity bit
|
||||
serial::setStopbits(tty, serCookie->getStopBits());
|
||||
serial::setBitsPerWord(tty, BitsPerWord::BITS_8);
|
||||
tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control
|
||||
serial::enableRead(tty);
|
||||
serial::ignoreCtrlLines(tty);
|
||||
|
||||
// Use non-canonical mode and clear echo flag
|
||||
tty.c_lflag &= ~(ICANON | ECHO);
|
||||
|
||||
// Non-blocking mode, use polling
|
||||
tty.c_cc[VTIME] = 0;
|
||||
tty.c_cc[VMIN] = 0;
|
||||
|
||||
serial::setBaudrate(tty, serCookie->getBaudrate());
|
||||
if (tcsetattr(serialPort, TCSANOW, &tty) != 0) {
|
||||
sif::warning << "ScexUartReader::initializeInterface: tcsetattr call failed with error ["
|
||||
<< errno << ", " << strerror(errno) << std::endl;
|
||||
}
|
||||
// Flush received and unread data
|
||||
tcflush(serialPort, TCIOFLUSH);
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StrComHandler::sendMessage(CookieIF* cookie, const uint8_t* sendData,
|
||||
size_t sendLen) {
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
if (state != InternalState::SLEEPING) {
|
||||
return BUSY;
|
||||
}
|
||||
}
|
||||
serial::flushRxBuf(serialPort);
|
||||
|
||||
const uint8_t* txFrame;
|
||||
size_t frameLen;
|
||||
datalinkLayer.encodeFrame(sendData, sendLen, &txFrame, frameLen);
|
||||
ssize_t bytesWritten = write(serialPort, txFrame, frameLen);
|
||||
if (bytesWritten != static_cast<ssize_t>(frameLen)) {
|
||||
sif::warning << "StrComHandler: Sending packet failed" << std::endl;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
// Hacky, but the alternatives look bleak. The raw data contains the information we need
|
||||
// and there are not too many special cases.
|
||||
if (sendData[0] == TMTC_ACTIONREQ) {
|
||||
// 1 is a firmware boot request and 7 is a reboot request. For both, no reply is expected.
|
||||
if (sendData[1] == 7 or sendData[1] == 1) {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
}
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
state = InternalState::POLL_ONE_REPLY;
|
||||
}
|
||||
// Unlock task to perform reply reading.
|
||||
semaphore.release();
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StrComHandler::getSendSuccess(CookieIF* cookie) { return returnvalue::OK; }
|
||||
|
||||
ReturnValue_t StrComHandler::requestReceiveMessage(CookieIF* cookie, size_t requestLen) {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StrComHandler::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) {
|
||||
// Consider it a configuration error if the task is not done with a command -> reply cycle
|
||||
// in time.
|
||||
bool replyWasReceived = false;
|
||||
{
|
||||
MutexGuard mg(lock);
|
||||
if (state != InternalState::SLEEPING) {
|
||||
return BUSY;
|
||||
}
|
||||
replyWasReceived = this->replyWasReceived;
|
||||
}
|
||||
if (not replyWasReceived) {
|
||||
*size = 0;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
if (replyResult == returnvalue::OK) {
|
||||
*buffer = const_cast<uint8_t*>(replyPtr);
|
||||
*size = replyLen;
|
||||
}
|
||||
return replyResult;
|
||||
}
|
||||
|
||||
ReturnValue_t StrComHandler::unlockAndEraseRegions(uint32_t from, uint32_t to) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
#if OBSW_DEBUG_STARTRACKER == 1
|
||||
ProgressPrinter progressPrinter("Unlock and erase", to - from);
|
||||
@ -595,17 +711,20 @@ ReturnValue_t StrHelper::unlockAndEraseRegions(uint32_t from, uint32_t to) {
|
||||
for (uint32_t idx = from; idx <= to; idx++) {
|
||||
unlockReq.region = idx;
|
||||
unlockReq.code = startracker::region_secrets::secret[idx];
|
||||
arc_pack_unlock_action_req(&unlockReq, commandBuffer, &size);
|
||||
sendAndRead(size, unlockReq.region);
|
||||
result = checkActionReply();
|
||||
arc_pack_unlock_action_req(&unlockReq, cmdBuf.data(), &size);
|
||||
result = sendAndRead(size, unlockReq.region);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
result = checkActionReply(replyLen);
|
||||
if (result != returnvalue::OK) {
|
||||
sif::warning << "StrHelper::unlockAndEraseRegions: Failed to unlock region with id "
|
||||
<< static_cast<unsigned int>(unlockReq.region) << std::endl;
|
||||
return result;
|
||||
}
|
||||
eraseReq.region = idx;
|
||||
arc_pack_erase_action_req(&eraseReq, commandBuffer, &size);
|
||||
result = sendAndRead(size, eraseReq.region, FLASH_ERASE_DELAY);
|
||||
arc_pack_erase_action_req(&eraseReq, cmdBuf.data(), &size);
|
||||
result = sendAndRead(size, eraseReq.region);
|
||||
if (result != returnvalue::OK) {
|
||||
sif::warning << "StrHelper::unlockAndEraseRegions: Failed to erase region with id "
|
||||
<< static_cast<unsigned int>(eraseReq.region) << std::endl;
|
||||
@ -617,3 +736,48 @@ ReturnValue_t StrHelper::unlockAndEraseRegions(uint32_t from, uint32_t to) {
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
||||
ReturnValue_t StrComHandler::handleSerialReception() {
|
||||
ssize_t bytesRead = read(serialPort, reinterpret_cast<void*>(recBuf.data()),
|
||||
static_cast<unsigned int>(recBuf.size()));
|
||||
if (bytesRead == 0) {
|
||||
return NO_SERIAL_DATA_READ;
|
||||
} else if (bytesRead < 0) {
|
||||
sif::warning << "StrComHandler: read call failed with error [" << errno << ", "
|
||||
<< strerror(errno) << "]" << std::endl;
|
||||
return FAILED;
|
||||
} else if (bytesRead >= static_cast<int>(recBuf.size())) {
|
||||
sif::error << "StrComHandler: Receive buffer too small for " << bytesRead << " bytes"
|
||||
<< std::endl;
|
||||
return FAILED;
|
||||
} else if (bytesRead > 0) {
|
||||
// sif::info << "Received " << bytesRead << " bytes from the STR" << std::endl;
|
||||
// arrayprinter::print(recBuf.data(), bytesRead);
|
||||
datalinkLayer.feedData(recBuf.data(), bytesRead);
|
||||
}
|
||||
return OK;
|
||||
}
|
||||
|
||||
ReturnValue_t StrComHandler::readOneReply(uint32_t failParameter) {
|
||||
ReturnValue_t result;
|
||||
uint32_t nextDelayMs = 1;
|
||||
replyTimeout.resetTimer();
|
||||
while (true) {
|
||||
handleSerialReception();
|
||||
result = datalinkLayer.checkRingBufForFrame(&replyPtr, replyLen);
|
||||
if (result == returnvalue::OK) {
|
||||
return returnvalue::OK;
|
||||
} else if (result != ArcsecDatalinkLayer::DEC_IN_PROGRESS) {
|
||||
triggerEvent(STR_HELPER_DEC_ERROR, result, failParameter);
|
||||
return DECODING_ERROR;
|
||||
}
|
||||
if (replyTimeout.hasTimedOut()) {
|
||||
triggerEvent(STR_COM_REPLY_TIMEOUT, failParameter, replyTimeout.getTimeoutMs());
|
||||
return RECEPTION_TIMEOUT;
|
||||
}
|
||||
TaskFactory::delayTask(nextDelayMs);
|
||||
if (nextDelayMs < 32) {
|
||||
nextDelayMs *= 2;
|
||||
}
|
||||
}
|
||||
}
|
@ -10,6 +10,8 @@
|
||||
#include "bsp_q7s/fs/SdCardManager.h"
|
||||
#endif
|
||||
|
||||
#include "arcsec/client/generated/actionreq.h"
|
||||
#include "arcsec/common/generated/tmtcstructs.h"
|
||||
#include "fsfw/devicehandlers/CookieIF.h"
|
||||
#include "fsfw/objectmanager/SystemObject.h"
|
||||
#include "fsfw/osal/linux/BinarySemaphore.h"
|
||||
@ -17,18 +19,36 @@
|
||||
#include "fsfw/tasks/ExecutableObjectIF.h"
|
||||
#include "fsfw_hal/linux/serial/SerialComIF.h"
|
||||
|
||||
extern "C" {
|
||||
#include "thirdparty/arcsec_star_tracker/client/generated/actionreq.h"
|
||||
#include "thirdparty/arcsec_star_tracker/common/generated/tmtcstructs.h"
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Helper class for the star tracker handler to accelerate large data transfers.
|
||||
*
|
||||
* @author J. Meier
|
||||
*/
|
||||
class StrHelper : public SystemObject, public ExecutableObjectIF {
|
||||
class StrComHandler : public SystemObject, public DeviceCommunicationIF, public ExecutableObjectIF {
|
||||
public:
|
||||
static const uint8_t INTERFACE_ID = CLASS_ID::STR_HELPER;
|
||||
|
||||
//! [EXPORT] : [COMMENT] SD card specified in path string not mounted
|
||||
static const ReturnValue_t SD_NOT_MOUNTED = MAKE_RETURN_CODE(1);
|
||||
//! [EXPORT] : [COMMENT] Specified file does not exist on filesystem
|
||||
static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(2);
|
||||
//! [EXPORT] : [COMMENT] Specified path does not exist
|
||||
static const ReturnValue_t PATH_NOT_EXISTS = MAKE_RETURN_CODE(3);
|
||||
//! [EXPORT] : [COMMENT] Failed to create download image or read flash file
|
||||
static const ReturnValue_t FILE_CREATION_FAILED = MAKE_RETURN_CODE(4);
|
||||
//! [EXPORT] : [COMMENT] Region in flash write/read reply does not match expected region
|
||||
static const ReturnValue_t REGION_MISMATCH = MAKE_RETURN_CODE(5);
|
||||
//! [EXPORT] : [COMMENT] Address in flash write/read reply does not match expected address
|
||||
static const ReturnValue_t ADDRESS_MISMATCH = MAKE_RETURN_CODE(6);
|
||||
//! [EXPORT] : [COMMENT] Length in flash write/read reply does not match expected length
|
||||
static const ReturnValue_t LENGTH_MISMATCH = MAKE_RETURN_CODE(7);
|
||||
//! [EXPORT] : [COMMENT] Status field in reply signals error
|
||||
static const ReturnValue_t STATUS_ERROR = MAKE_RETURN_CODE(8);
|
||||
//! [EXPORT] : [COMMENT] Reply has invalid type ID (should be of action reply type)
|
||||
static const ReturnValue_t INVALID_TYPE_ID = MAKE_RETURN_CODE(9);
|
||||
static const ReturnValue_t RECEPTION_TIMEOUT = MAKE_RETURN_CODE(10);
|
||||
static const ReturnValue_t DECODING_ERROR = MAKE_RETURN_CODE(11);
|
||||
|
||||
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::STR_HELPER;
|
||||
|
||||
//! [EXPORT] : [COMMENT] Image upload failed
|
||||
@ -57,39 +77,36 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
|
||||
//! P1: Return code of failed communication interface read call
|
||||
//! P1: Upload/download position for which the read call failed
|
||||
static const Event STR_HELPER_COM_ERROR = MAKE_EVENT(10, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Star tracker did not send replies (maybe device is powered off)
|
||||
//! P1: Position of upload or download packet for which no reply was sent
|
||||
static const Event STR_HELPER_NO_REPLY = MAKE_EVENT(11, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Star tracker did not send a valid reply for a certain timeout.
|
||||
//! P1: Position of upload or download packet for which the packet wa sent. P2: Timeout
|
||||
static const Event STR_COM_REPLY_TIMEOUT = MAKE_EVENT(11, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Error during decoding of received reply occurred
|
||||
// P1: Return value of decoding function
|
||||
// P2: Position of upload/download packet, or address of flash write/read request
|
||||
static const Event STR_HELPER_DEC_ERROR = MAKE_EVENT(12, severity::LOW);
|
||||
//! P1: Return value of decoding function
|
||||
//! P2: Position of upload/download packet, or address of flash write/read request
|
||||
static const Event STR_HELPER_DEC_ERROR = MAKE_EVENT(13, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Position mismatch
|
||||
//! P1: The expected position and thus the position for which the image upload/download failed
|
||||
static const Event POSITION_MISMATCH = MAKE_EVENT(13, severity::LOW);
|
||||
static const Event POSITION_MISMATCH = MAKE_EVENT(14, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Specified file does not exist
|
||||
//! P1: Internal state of str helper
|
||||
static const Event STR_HELPER_FILE_NOT_EXISTS = MAKE_EVENT(14, severity::LOW);
|
||||
static const Event STR_HELPER_FILE_NOT_EXISTS = MAKE_EVENT(15, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Sending packet to star tracker failed
|
||||
//! P1: Return code of communication interface sendMessage function
|
||||
//! P2: Position of upload/download packet, or address of flash write/read request for which
|
||||
//! sending failed
|
||||
static const Event STR_HELPER_SENDING_PACKET_FAILED = MAKE_EVENT(15, severity::LOW);
|
||||
static const Event STR_HELPER_SENDING_PACKET_FAILED = MAKE_EVENT(16, severity::LOW);
|
||||
//! [EXPORT] : [COMMENT] Communication interface requesting reply failed
|
||||
//! P1: Return code of failed request
|
||||
//! P1: Upload/download position, or address of flash write/read request for which transmission
|
||||
//! failed
|
||||
static const Event STR_HELPER_REQUESTING_MSG_FAILED = MAKE_EVENT(16, severity::LOW);
|
||||
static const Event STR_HELPER_REQUESTING_MSG_FAILED = MAKE_EVENT(17, severity::LOW);
|
||||
|
||||
StrHelper(object_id_t objectId);
|
||||
virtual ~StrHelper();
|
||||
StrComHandler(object_id_t objectId);
|
||||
virtual ~StrComHandler();
|
||||
|
||||
ReturnValue_t initialize() override;
|
||||
ReturnValue_t performOperation(uint8_t operationCode = 0) override;
|
||||
|
||||
ReturnValue_t setComIF(DeviceCommunicationIF* communicationInterface_);
|
||||
void setComCookie(CookieIF* comCookie_);
|
||||
|
||||
/**
|
||||
* @brief Starts sequence to upload image to star tracker
|
||||
*
|
||||
@ -148,26 +165,8 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
|
||||
void enableTimestamping();
|
||||
|
||||
private:
|
||||
static const uint8_t INTERFACE_ID = CLASS_ID::STR_HELPER;
|
||||
|
||||
//! [EXPORT] : [COMMENT] SD card specified in path string not mounted
|
||||
static const ReturnValue_t SD_NOT_MOUNTED = MAKE_RETURN_CODE(0xA0);
|
||||
//! [EXPORT] : [COMMENT] Specified file does not exist on filesystem
|
||||
static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xA1);
|
||||
//! [EXPORT] : [COMMENT] Specified path does not exist
|
||||
static const ReturnValue_t PATH_NOT_EXISTS = MAKE_RETURN_CODE(0xA2);
|
||||
//! [EXPORT] : [COMMENT] Failed to create download image or read flash file
|
||||
static const ReturnValue_t FILE_CREATION_FAILED = MAKE_RETURN_CODE(0xA3);
|
||||
//! [EXPORT] : [COMMENT] Region in flash write/read reply does not match expected region
|
||||
static const ReturnValue_t REGION_MISMATCH = MAKE_RETURN_CODE(0xA4);
|
||||
//! [EXPORT] : [COMMENT] Address in flash write/read reply does not match expected address
|
||||
static const ReturnValue_t ADDRESS_MISMATCH = MAKE_RETURN_CODE(0xA5);
|
||||
//! [EXPORT] : [COMMENT] Length in flash write/read reply does not match expected length
|
||||
static const ReturnValue_t LENGTH_MISMATCH = MAKE_RETURN_CODE(0xA6);
|
||||
//! [EXPORT] : [COMMENT] Status field in reply signals error
|
||||
static const ReturnValue_t STATUS_ERROR = MAKE_RETURN_CODE(0xA7);
|
||||
//! [EXPORT] : [COMMENT] Reply has invalid type ID (should be of action reply type)
|
||||
static const ReturnValue_t INVALID_TYPE_ID = MAKE_RETURN_CODE(0xA8);
|
||||
//! [EXPORT] : [SKIP]
|
||||
static constexpr ReturnValue_t NO_SERIAL_DATA_READ = MAKE_RETURN_CODE(128);
|
||||
|
||||
// Size of one image part which can be sent per action request
|
||||
static const size_t SIZE_IMAGE_PART = 1024;
|
||||
@ -179,25 +178,34 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
|
||||
|
||||
static const uint32_t MAX_POLLS = 10000;
|
||||
|
||||
static const uint8_t ACTION_DATA_OFFSET = 2;
|
||||
static const uint8_t POS_OFFSET = 2;
|
||||
static const uint8_t IMAGE_DATA_OFFSET = 5;
|
||||
static const uint8_t FLASH_READ_DATA_OFFSET = 8;
|
||||
static const uint8_t REGION_OFFSET = 2;
|
||||
static const uint8_t ADDRESS_OFFSET = 3;
|
||||
static const uint8_t LENGTH_OFFSET = 7;
|
||||
static const uint8_t ACTION_DATA_OFFSET = 3;
|
||||
static const uint8_t POS_OFFSET = 3;
|
||||
static const uint8_t IMAGE_DATA_OFFSET = 6;
|
||||
static const uint8_t FLASH_READ_DATA_OFFSET = 9;
|
||||
static const uint8_t REGION_OFFSET = 3;
|
||||
static const uint8_t ADDRESS_OFFSET = 4;
|
||||
static const size_t CHUNK_SIZE = 1024;
|
||||
static const size_t CONFIG_MAX_DOWNLOAD_RETRIES = 3;
|
||||
static const uint32_t FLASH_ERASE_DELAY = 500;
|
||||
|
||||
enum class InternalState { IDLE, UPLOAD_IMAGE, DOWNLOAD_IMAGE, FLASH_READ, FIRMWARE_UPDATE };
|
||||
enum class InternalState {
|
||||
SLEEPING,
|
||||
POLL_ONE_REPLY,
|
||||
UPLOAD_IMAGE,
|
||||
DOWNLOAD_IMAGE,
|
||||
FLASH_READ,
|
||||
FIRMWARE_UPDATE
|
||||
};
|
||||
|
||||
InternalState internalState = InternalState::IDLE;
|
||||
InternalState state = InternalState::SLEEPING;
|
||||
|
||||
ArcsecDatalinkLayer datalinkLayer;
|
||||
|
||||
MutexIF *lock;
|
||||
BinarySemaphore semaphore;
|
||||
|
||||
Countdown replyTimeout = Countdown(20);
|
||||
|
||||
struct UploadImage {
|
||||
// Name including absolute path of image to upload
|
||||
std::string uploadFile;
|
||||
@ -238,10 +246,16 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
|
||||
FlashRead flashRead;
|
||||
|
||||
#ifdef XIPHOS_Q7S
|
||||
SdCardManager* sdcMan = nullptr;
|
||||
SdCardManager *sdcMan = nullptr;
|
||||
#endif
|
||||
|
||||
uint8_t commandBuffer[startracker::MAX_FRAME_SIZE];
|
||||
std::array<uint8_t, startracker::MAX_FRAME_SIZE> cmdBuf{};
|
||||
std::array<uint8_t, 4096> recBuf{};
|
||||
|
||||
bool replyWasReceived = false;
|
||||
const uint8_t *replyPtr = nullptr;
|
||||
size_t replyLen = 0;
|
||||
ReturnValue_t replyResult = returnvalue::OK;
|
||||
|
||||
bool terminate = false;
|
||||
|
||||
@ -251,17 +265,20 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
|
||||
bool timestamping = true;
|
||||
#endif
|
||||
|
||||
/**
|
||||
* UART communication object responsible for low level access of star tracker
|
||||
* Must be set by star tracker handler
|
||||
*/
|
||||
SerialComIF* uartComIF = nullptr;
|
||||
// Communication cookie. Must be set by the star tracker handler
|
||||
CookieIF* comCookie = nullptr;
|
||||
int serialPort = 0;
|
||||
struct termios tty = {};
|
||||
|
||||
// Queue id of raw data receiver
|
||||
MessageQueueId_t rawDataReceiver = MessageQueueIF::NO_QUEUE;
|
||||
|
||||
ReturnValue_t initializeInterface(CookieIF *cookie) override;
|
||||
ReturnValue_t sendMessage(CookieIF *cookie, const uint8_t *sendData, size_t sendLen) override;
|
||||
ReturnValue_t getSendSuccess(CookieIF *cookie) override;
|
||||
ReturnValue_t requestReceiveMessage(CookieIF *cookie, size_t requestLen) override;
|
||||
ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **buffer, size_t *size) override;
|
||||
|
||||
ReturnValue_t handleSerialReception();
|
||||
|
||||
/**
|
||||
* @brief Performs image uploading
|
||||
*/
|
||||
@ -302,21 +319,23 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
|
||||
/**
|
||||
* @brief Sends packet to the star tracker and reads reply by using the communication
|
||||
* interface
|
||||
*
|
||||
* @details
|
||||
* The reply frame is stored in the data link layer helper. A pointer to the start of the frame
|
||||
* is assigned to the @replyPtr member of this class. The frame length will be assigned to
|
||||
* the @replyLen member.
|
||||
* @param size Size of data beforehand written to the commandBuffer
|
||||
* @param parameter Parameter 2 of trigger event function
|
||||
* @param delayMs Delay in milliseconds between send and receive call
|
||||
*
|
||||
* @return returnvalue::OK if successful, otherwise returnvalue::FAILED
|
||||
*/
|
||||
ReturnValue_t sendAndRead(size_t size, uint32_t parameter, uint32_t delayMs = 0);
|
||||
ReturnValue_t sendAndRead(size_t size, uint32_t parameter);
|
||||
|
||||
/**
|
||||
* @brief Checks the header (type id and status fields) of the action reply
|
||||
*
|
||||
* @return returnvalue::OK if reply confirms success of packet transfer, otherwise REUTRN_FAILED
|
||||
*/
|
||||
ReturnValue_t checkActionReply();
|
||||
ReturnValue_t checkActionReply(size_t replySize);
|
||||
|
||||
/**
|
||||
* @brief Checks the position field in a star tracker upload/download reply.
|
||||
@ -345,6 +364,15 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
|
||||
*
|
||||
*/
|
||||
ReturnValue_t unlockAndEraseRegions(uint32_t from, uint32_t to);
|
||||
|
||||
/**
|
||||
* The reply frame is stored in the data link layer helper. A pointer to the start of the frame
|
||||
* is assigned to the @replyPtr member of this class. The frame length will be assigned to
|
||||
* the @replyLen member.
|
||||
* @param failParameter
|
||||
* @return
|
||||
*/
|
||||
ReturnValue_t readOneReply(uint32_t failParameter);
|
||||
};
|
||||
|
||||
#endif /* BSP_Q7S_DEVICES_STRHELPER_H_ */
|
7
linux/devices/startracker/helpers.cpp
Normal file
7
linux/devices/startracker/helpers.cpp
Normal file
@ -0,0 +1,7 @@
|
||||
#include "helpers.h"
|
||||
|
||||
uint8_t str::getReplyFrameType(const uint8_t* rawFrame) { return rawFrame[0]; }
|
||||
|
||||
uint8_t str::getId(const uint8_t* rawFrame) { return rawFrame[1]; }
|
||||
|
||||
uint8_t str::getStatusField(const uint8_t* rawFrame) { return rawFrame[2]; }
|
17
linux/devices/startracker/helpers.h
Normal file
17
linux/devices/startracker/helpers.h
Normal file
@ -0,0 +1,17 @@
|
||||
#ifndef LINUX_DEVICES_STARTRACKER_HELPERS_H_
|
||||
#define LINUX_DEVICES_STARTRACKER_HELPERS_H_
|
||||
|
||||
#include "arcsec/common/genericstructs.h"
|
||||
|
||||
namespace str {
|
||||
|
||||
/**
|
||||
* @brief Returns the frame type field of a decoded frame.
|
||||
*/
|
||||
uint8_t getReplyFrameType(const uint8_t* rawFrame);
|
||||
uint8_t getId(const uint8_t* rawFrame);
|
||||
uint8_t getStatusField(const uint8_t* rawFrame);
|
||||
|
||||
} // namespace str
|
||||
|
||||
#endif /* LINUX_DEVICES_STARTRACKER_HELPERS_H_ */
|
@ -1,6 +1,6 @@
|
||||
#include "StarTrackerJsonCommands.h"
|
||||
#include "strJsonCommands.h"
|
||||
|
||||
#include "ArcsecJsonKeys.h"
|
||||
#include "arcsecJsonKeys.h"
|
||||
|
||||
Limits::Limits() : ArcsecJsonParamBase(arcseckeys::LIMITS) {}
|
||||
|
@ -1,7 +1,7 @@
|
||||
/**
|
||||
* @brief Auto-generated event translation file. Contains 280 translations.
|
||||
* @brief Auto-generated event translation file. Contains 279 translations.
|
||||
* @details
|
||||
* Generated on: 2023-03-23 10:28:33
|
||||
* Generated on: 2023-03-24 14:59:06
|
||||
*/
|
||||
#include "translateEvents.h"
|
||||
|
||||
@ -173,7 +173,7 @@ const char *FIRMWARE_UPDATE_SUCCESSFUL_STRING = "FIRMWARE_UPDATE_SUCCESSFUL";
|
||||
const char *FIRMWARE_UPDATE_FAILED_STRING = "FIRMWARE_UPDATE_FAILED";
|
||||
const char *STR_HELPER_READING_REPLY_FAILED_STRING = "STR_HELPER_READING_REPLY_FAILED";
|
||||
const char *STR_HELPER_COM_ERROR_STRING = "STR_HELPER_COM_ERROR";
|
||||
const char *STR_HELPER_NO_REPLY_STRING = "STR_HELPER_NO_REPLY";
|
||||
const char *STR_COM_REPLY_TIMEOUT_STRING = "STR_COM_REPLY_TIMEOUT";
|
||||
const char *STR_HELPER_DEC_ERROR_STRING = "STR_HELPER_DEC_ERROR";
|
||||
const char *POSITION_MISMATCH_STRING = "POSITION_MISMATCH";
|
||||
const char *STR_HELPER_FILE_NOT_EXISTS_STRING = "STR_HELPER_FILE_NOT_EXISTS";
|
||||
@ -620,16 +620,16 @@ const char *translateEvents(Event event) {
|
||||
case (12510):
|
||||
return STR_HELPER_COM_ERROR_STRING;
|
||||
case (12511):
|
||||
return STR_HELPER_NO_REPLY_STRING;
|
||||
case (12512):
|
||||
return STR_HELPER_DEC_ERROR_STRING;
|
||||
return STR_COM_REPLY_TIMEOUT_STRING;
|
||||
case (12513):
|
||||
return POSITION_MISMATCH_STRING;
|
||||
return STR_HELPER_DEC_ERROR_STRING;
|
||||
case (12514):
|
||||
return STR_HELPER_FILE_NOT_EXISTS_STRING;
|
||||
return POSITION_MISMATCH_STRING;
|
||||
case (12515):
|
||||
return STR_HELPER_SENDING_PACKET_FAILED_STRING;
|
||||
return STR_HELPER_FILE_NOT_EXISTS_STRING;
|
||||
case (12516):
|
||||
return STR_HELPER_SENDING_PACKET_FAILED_STRING;
|
||||
case (12517):
|
||||
return STR_HELPER_REQUESTING_MSG_FAILED_STRING;
|
||||
case (12600):
|
||||
return MPSOC_FLASH_WRITE_FAILED_STRING;
|
||||
|
@ -2,7 +2,7 @@
|
||||
* @brief Auto-generated object translation file.
|
||||
* @details
|
||||
* Contains 173 translations.
|
||||
* Generated on: 2023-03-21 23:59:36
|
||||
* Generated on: 2023-03-24 14:59:06
|
||||
*/
|
||||
#include "translateObjects.h"
|
||||
|
||||
@ -49,7 +49,7 @@ const char *PLPCDU_HANDLER_STRING = "PLPCDU_HANDLER";
|
||||
const char *RAD_SENSOR_STRING = "RAD_SENSOR";
|
||||
const char *PLOC_UPDATER_STRING = "PLOC_UPDATER";
|
||||
const char *PLOC_MEMORY_DUMPER_STRING = "PLOC_MEMORY_DUMPER";
|
||||
const char *STR_HELPER_STRING = "STR_HELPER";
|
||||
const char *STR_COM_IF_STRING = "STR_COM_IF";
|
||||
const char *PLOC_MPSOC_HELPER_STRING = "PLOC_MPSOC_HELPER";
|
||||
const char *AXI_PTME_CONFIG_STRING = "AXI_PTME_CONFIG";
|
||||
const char *PTME_CONFIG_STRING = "PTME_CONFIG";
|
||||
@ -85,6 +85,7 @@ const char *RTD_13_IC16_PLPCDU_HEATSPREADER_STRING = "RTD_13_IC16_PLPCDU_HEATSPR
|
||||
const char *RTD_14_IC17_TCS_BOARD_STRING = "RTD_14_IC17_TCS_BOARD";
|
||||
const char *RTD_15_IC18_IMTQ_STRING = "RTD_15_IC18_IMTQ";
|
||||
const char *SYRLINKS_HANDLER_STRING = "SYRLINKS_HANDLER";
|
||||
const char *SYRLINKS_COM_HANDLER_STRING = "SYRLINKS_COM_HANDLER";
|
||||
const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF";
|
||||
const char *GPIO_IF_STRING = "GPIO_IF";
|
||||
const char *SCEX_UART_READER_STRING = "SCEX_UART_READER";
|
||||
@ -176,7 +177,6 @@ const char *LOG_STORE_AND_TM_TASK_STRING = "LOG_STORE_AND_TM_TASK";
|
||||
const char *HK_STORE_AND_TM_TASK_STRING = "HK_STORE_AND_TM_TASK";
|
||||
const char *CFDP_STORE_AND_TM_TASK_STRING = "CFDP_STORE_AND_TM_TASK";
|
||||
const char *DOWNLINK_RAM_STORE_STRING = "DOWNLINK_RAM_STORE";
|
||||
const char *CCSDS_IP_CORE_BRIDGE_STRING = "CCSDS_IP_CORE_BRIDGE";
|
||||
const char *THERMAL_TEMP_INSERTER_STRING = "THERMAL_TEMP_INSERTER";
|
||||
const char *NO_OBJECT_STRING = "NO_OBJECT";
|
||||
|
||||
@ -269,7 +269,7 @@ const char *translateObject(object_id_t object) {
|
||||
case 0x44330001:
|
||||
return PLOC_MEMORY_DUMPER_STRING;
|
||||
case 0x44330002:
|
||||
return STR_HELPER_STRING;
|
||||
return STR_COM_IF_STRING;
|
||||
case 0x44330003:
|
||||
return PLOC_MPSOC_HELPER_STRING;
|
||||
case 0x44330004:
|
||||
@ -340,6 +340,8 @@ const char *translateObject(object_id_t object) {
|
||||
return RTD_15_IC18_IMTQ_STRING;
|
||||
case 0x445300A3:
|
||||
return SYRLINKS_HANDLER_STRING;
|
||||
case 0x445300A4:
|
||||
return SYRLINKS_COM_HANDLER_STRING;
|
||||
case 0x49000000:
|
||||
return ARDUINO_COM_IF_STRING;
|
||||
case 0x49010005:
|
||||
@ -522,8 +524,6 @@ const char *translateObject(object_id_t object) {
|
||||
return CFDP_STORE_AND_TM_TASK_STRING;
|
||||
case 0x73040004:
|
||||
return DOWNLINK_RAM_STORE_STRING;
|
||||
case 0x73500000:
|
||||
return CCSDS_IP_CORE_BRIDGE_STRING;
|
||||
case 0x90000003:
|
||||
return THERMAL_TEMP_INSERTER_STRING;
|
||||
case 0xFFFFFFFF:
|
||||
|
@ -1,5 +1,6 @@
|
||||
#include <fsfw_hal/linux/uio/UioMapper.h>
|
||||
#include <linux/ipcore/PapbVcInterface.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include "fsfw/serviceinterface/ServiceInterface.h"
|
||||
|
||||
@ -15,47 +16,67 @@ PapbVcInterface::~PapbVcInterface() {}
|
||||
|
||||
ReturnValue_t PapbVcInterface::initialize() {
|
||||
UioMapper uioMapper(uioFile, mapNum);
|
||||
return uioMapper.getMappedAdress(&vcBaseReg, UioMapper::Permissions::WRITE_ONLY);
|
||||
uint32_t* baseReg;
|
||||
ReturnValue_t result = uioMapper.getMappedAdress(&baseReg, UioMapper::Permissions::WRITE_ONLY);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
vcBaseReg = baseReg;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
ReturnValue_t PapbVcInterface::write(const uint8_t* data, size_t size) {
|
||||
if (pollPapbBusySignal() == returnvalue::OK) {
|
||||
if (pollPapbBusySignal(0, 0) == returnvalue::OK) {
|
||||
startPacketTransfer();
|
||||
} else {
|
||||
return DirectTmSinkIF::IS_BUSY;
|
||||
}
|
||||
for (size_t idx = 0; idx < size; idx++) {
|
||||
if (pollPapbBusySignal() == returnvalue::OK) {
|
||||
*(vcBaseReg + DATA_REG_OFFSET) = static_cast<uint32_t>(*(data + idx));
|
||||
if (pollPapbBusySignal(10, 10) == returnvalue::OK) {
|
||||
*(vcBaseReg + DATA_REG_OFFSET) = static_cast<uint32_t>(data[idx]);
|
||||
} else {
|
||||
sif::warning << "PapbVcInterface::write: Only written " << idx << " of " << size << " data"
|
||||
<< std::endl;
|
||||
abortPacketTransfer();
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
}
|
||||
if (pollPapbBusySignal() == returnvalue::OK) {
|
||||
endPacketTransfer();
|
||||
if (pollPapbBusySignal(10, 10) == returnvalue::OK) {
|
||||
completePacketTransfer();
|
||||
} else {
|
||||
abortPacketTransfer();
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void PapbVcInterface::startPacketTransfer() { *vcBaseReg = CONFIG_START; }
|
||||
|
||||
void PapbVcInterface::endPacketTransfer() { *vcBaseReg = CONFIG_END; }
|
||||
void PapbVcInterface::completePacketTransfer() { *vcBaseReg = CONFIG_END; }
|
||||
|
||||
ReturnValue_t PapbVcInterface::pollPapbBusySignal() const {
|
||||
ReturnValue_t PapbVcInterface::pollPapbBusySignal(uint32_t maxPollRetries,
|
||||
uint32_t retryDelayUs) const {
|
||||
gpio::Levels papbBusyState = gpio::Levels::LOW;
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
ReturnValue_t result;
|
||||
uint32_t busyIdx = 0;
|
||||
|
||||
/** Check if PAPB interface is ready to receive data */
|
||||
result = gpioComIF->readGpio(papbBusyId, papbBusyState);
|
||||
if (result != returnvalue::OK) {
|
||||
sif::warning << "PapbVcInterface::pollPapbBusySignal: Failed to read papb busy signal"
|
||||
<< std::endl;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
if (papbBusyState == gpio::Levels::LOW) {
|
||||
return PAPB_BUSY;
|
||||
}
|
||||
while (true) {
|
||||
/** Check if PAPB interface is ready to receive data */
|
||||
result = gpioComIF->readGpio(papbBusyId, papbBusyState);
|
||||
if (result != returnvalue::OK) {
|
||||
sif::warning << "PapbVcInterface::pollPapbBusySignal: Failed to read papb busy signal"
|
||||
<< std::endl;
|
||||
return returnvalue::FAILED;
|
||||
}
|
||||
if (papbBusyState == gpio::Levels::HIGH) {
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
busyIdx++;
|
||||
if (busyIdx >= maxPollRetries) {
|
||||
return PAPB_BUSY;
|
||||
}
|
||||
|
||||
usleep(retryDelayUs);
|
||||
}
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
@ -79,7 +100,9 @@ void PapbVcInterface::isVcInterfaceBufferEmpty() {
|
||||
return;
|
||||
}
|
||||
|
||||
bool PapbVcInterface::isBusy() const { return pollPapbBusySignal() == PAPB_BUSY; }
|
||||
bool PapbVcInterface::isBusy() const { return pollPapbBusySignal(0, 0) == PAPB_BUSY; }
|
||||
|
||||
void PapbVcInterface::cancelTransfer() { abortPacketTransfer(); }
|
||||
|
||||
ReturnValue_t PapbVcInterface::sendTestFrame() {
|
||||
/** Size of one complete transfer frame data field amounts to 1105 bytes */
|
||||
@ -97,3 +120,5 @@ ReturnValue_t PapbVcInterface::sendTestFrame() {
|
||||
|
||||
return returnvalue::OK;
|
||||
}
|
||||
|
||||
void PapbVcInterface::abortPacketTransfer() { *vcBaseReg = CONFIG_ABORT; }
|
||||
|
@ -41,6 +41,8 @@ class PapbVcInterface : public VirtualChannelIF {
|
||||
*/
|
||||
ReturnValue_t write(const uint8_t* data, size_t size) override;
|
||||
|
||||
void cancelTransfer() override;
|
||||
|
||||
ReturnValue_t initialize() override;
|
||||
|
||||
private:
|
||||
@ -51,16 +53,21 @@ class PapbVcInterface : public VirtualChannelIF {
|
||||
/**
|
||||
* Configuration bits:
|
||||
* bit[1:0]: Size of data (1,2,3 or 4 bytes). 1 Byte <=> b00
|
||||
* bit[2]: Set this bit to 1 to abort a transfered packet
|
||||
* bit[2]: Set this bit to 1 to abort a transferred packet
|
||||
* bit[3]: Signals to VcInterface the start of a new telemetry packet
|
||||
*/
|
||||
static const uint32_t CONFIG_START = 0x8;
|
||||
static constexpr uint32_t CONFIG_START = 0b00001000;
|
||||
|
||||
/**
|
||||
* Abort a transferred packet.
|
||||
*/
|
||||
static constexpr uint32_t CONFIG_ABORT = 0b00000100;
|
||||
|
||||
/**
|
||||
* Writing this word to the VcInterface base address signals to the virtual channel interface
|
||||
* that a complete tm packet has been transferred.
|
||||
*/
|
||||
static const uint32_t CONFIG_END = 0x0;
|
||||
static constexpr uint32_t CONFIG_END = 0x0;
|
||||
|
||||
/**
|
||||
* Writing to this offset within the memory space of a virtual channel will insert data for
|
||||
@ -79,7 +86,7 @@ class PapbVcInterface : public VirtualChannelIF {
|
||||
std::string uioFile;
|
||||
int mapNum = 0;
|
||||
|
||||
uint32_t* vcBaseReg = nullptr;
|
||||
volatile uint32_t* vcBaseReg = nullptr;
|
||||
|
||||
uint32_t vcOffset = 0;
|
||||
|
||||
@ -89,11 +96,13 @@ class PapbVcInterface : public VirtualChannelIF {
|
||||
*/
|
||||
void startPacketTransfer();
|
||||
|
||||
void abortPacketTransfer();
|
||||
|
||||
/**
|
||||
* @brief This function sends the config byte to the virtual channel interface of the PTME
|
||||
* IP Core to signal the end of a packet transfer.
|
||||
*/
|
||||
void endPacketTransfer();
|
||||
void completePacketTransfer();
|
||||
|
||||
/**
|
||||
* @brief This function reads the papb busy signal indicating whether the virtual channel
|
||||
@ -102,7 +111,7 @@ class PapbVcInterface : public VirtualChannelIF {
|
||||
*
|
||||
* @return returnvalue::OK when ready to receive data else PAPB_BUSY.
|
||||
*/
|
||||
ReturnValue_t pollPapbBusySignal() const;
|
||||
ReturnValue_t pollPapbBusySignal(uint32_t maxPollRetries, uint32_t retryDelayUs) const;
|
||||
|
||||
/**
|
||||
* @brief This function can be used for debugging to check whether there are packets in
|
||||
|
@ -20,7 +20,6 @@ ReturnValue_t Ptme::initialize() {
|
||||
}
|
||||
|
||||
ReturnValue_t Ptme::writeToVc(uint8_t vcId, const uint8_t* data, size_t size) {
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
VcInterfaceMapIter vcInterfaceMapIter = vcInterfaceMap.find(vcId);
|
||||
if (vcInterfaceMapIter == vcInterfaceMap.end()) {
|
||||
sif::warning << "Ptme::writeToVc: No virtual channel interface found for the virtual "
|
||||
@ -28,8 +27,7 @@ ReturnValue_t Ptme::writeToVc(uint8_t vcId, const uint8_t* data, size_t size) {
|
||||
<< static_cast<unsigned int>(vcId) << std::endl;
|
||||
return UNKNOWN_VC_ID;
|
||||
}
|
||||
result = vcInterfaceMapIter->second->write(data, size);
|
||||
return result;
|
||||
return vcInterfaceMapIter->second->write(data, size);
|
||||
}
|
||||
|
||||
void Ptme::addVcInterface(VcId_t vcId, VirtualChannelIF* vc) {
|
||||
@ -62,3 +60,11 @@ bool Ptme::isBusy(uint8_t vcId) const {
|
||||
}
|
||||
return vcInterfaceMapIter->second->isBusy();
|
||||
}
|
||||
|
||||
void Ptme::cancelTransfer(uint8_t vcId) {
|
||||
VcInterfaceMapIter vcInterfaceMapIter = vcInterfaceMap.find(vcId);
|
||||
if (vcInterfaceMapIter == vcInterfaceMap.end()) {
|
||||
return;
|
||||
}
|
||||
return vcInterfaceMapIter->second->cancelTransfer();
|
||||
}
|
||||
|
@ -36,6 +36,7 @@ class Ptme : public PtmeIF, public SystemObject {
|
||||
ReturnValue_t initialize() override;
|
||||
ReturnValue_t writeToVc(uint8_t vcId, const uint8_t* data, size_t size) override;
|
||||
bool isBusy(uint8_t vcId) const override;
|
||||
void cancelTransfer(uint8_t vcId) override;
|
||||
|
||||
/**
|
||||
* @brief This function adds the reference to a virtual channel interface to the vcInterface
|
||||
|
@ -23,6 +23,7 @@ class PtmeIF {
|
||||
*/
|
||||
virtual ReturnValue_t writeToVc(uint8_t vcId, const uint8_t* data, size_t size) = 0;
|
||||
virtual bool isBusy(uint8_t vcId) const = 0;
|
||||
virtual void cancelTransfer(uint8_t vcId) = 0;
|
||||
};
|
||||
|
||||
#endif /* LINUX_OBC_PTMEIF_H_ */
|
||||
|
@ -18,6 +18,7 @@ class VirtualChannelIF : public DirectTmSinkIF {
|
||||
virtual ~VirtualChannelIF(){};
|
||||
|
||||
virtual ReturnValue_t initialize() = 0;
|
||||
virtual void cancelTransfer() = 0;
|
||||
};
|
||||
|
||||
#endif /* LINUX_OBC_VCINTERFACEIF_H_ */
|
||||
|
@ -8,6 +8,9 @@
|
||||
#include "ObjectFactory.h"
|
||||
#include "eive/objects.h"
|
||||
|
||||
PosixThreadArgs scheduling::RR_SCHEDULING = {.policy = SchedulingPolicy::RR};
|
||||
PosixThreadArgs scheduling::NORMAL_SCHEDULING;
|
||||
|
||||
void scheduling::scheduleScexReader(TaskFactory& factory, PeriodicTaskIF*& scexReaderTask) {
|
||||
using namespace scheduling;
|
||||
ReturnValue_t result = returnvalue::OK;
|
||||
@ -18,8 +21,9 @@ void scheduling::scheduleScexReader(TaskFactory& factory, PeriodicTaskIF*& scexR
|
||||
#endif
|
||||
|
||||
result = returnvalue::OK;
|
||||
scexReaderTask = factory.createPeriodicTask(
|
||||
"SCEX_UART_READER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
|
||||
scexReaderTask =
|
||||
factory.createPeriodicTask("SCEX_UART_READER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0,
|
||||
missedDeadlineFunc, &NORMAL_SCHEDULING);
|
||||
result = scexReaderTask->addComponent(objects::SCEX_UART_READER);
|
||||
if (result != returnvalue::OK) {
|
||||
printAddObjectError("SCEX_UART_READER", objects::SCEX_UART_READER);
|
||||
|
@ -1,8 +1,13 @@
|
||||
#pragma once
|
||||
|
||||
#include <fsfw/osal/linux/PosixThread.h>
|
||||
#include <fsfw/tasks/TaskFactory.h>
|
||||
|
||||
namespace scheduling {
|
||||
|
||||
extern PosixThreadArgs RR_SCHEDULING;
|
||||
extern PosixThreadArgs NORMAL_SCHEDULING;
|
||||
|
||||
void scheduleScexDev(PeriodicTaskIF*& scexDevHandler);
|
||||
void scheduleScexReader(TaskFactory& factory, PeriodicTaskIF*& scexReaderTask);
|
||||
void addMpsocSupvHandlers(PeriodicTaskIF* task);
|
||||
|
@ -605,7 +605,6 @@ void ThermalController::copySus() {
|
||||
}
|
||||
|
||||
void ThermalController::copyDevices() {
|
||||
lp_var_t<float> tempQ7s = lp_var_t<float>(objects::CORE_CONTROLLER, core::PoolIds::TEMPERATURE);
|
||||
{
|
||||
PoolReadGuard pg(&tempQ7s, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() == returnvalue::OK) {
|
||||
@ -618,8 +617,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<int16_t> battTemp1 =
|
||||
lp_var_t<int16_t>(objects::BPX_BATT_HANDLER, BpxBattery::BATT_TEMP_1);
|
||||
PoolReadGuard pg(&battTemp1, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read battery temperature 1" << std::endl;
|
||||
@ -632,8 +629,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<int16_t> battTemp2 =
|
||||
lp_var_t<int16_t>(objects::BPX_BATT_HANDLER, BpxBattery::BATT_TEMP_2);
|
||||
PoolReadGuard pg(&battTemp2, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read battery temperature 2" << std::endl;
|
||||
@ -646,8 +641,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<int16_t> battTemp3 =
|
||||
lp_var_t<int16_t>(objects::BPX_BATT_HANDLER, BpxBattery::BATT_TEMP_3);
|
||||
PoolReadGuard pg(&battTemp3, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read battery temperature 3" << std::endl;
|
||||
@ -660,8 +653,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<int16_t> battTemp4 =
|
||||
lp_var_t<int16_t>(objects::BPX_BATT_HANDLER, BpxBattery::BATT_TEMP_4);
|
||||
PoolReadGuard pg(&battTemp4, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read battery temperature 4" << std::endl;
|
||||
@ -674,7 +665,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<int32_t> tempRw1 = lp_var_t<int32_t>(objects::RW1, rws::TEMPERATURE_C);
|
||||
PoolReadGuard pg(&tempRw1, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read reaction wheel 1 temperature" << std::endl;
|
||||
@ -687,7 +677,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<int32_t> tempRw2 = lp_var_t<int32_t>(objects::RW2, rws::TEMPERATURE_C);
|
||||
PoolReadGuard pg(&tempRw2, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read reaction wheel 2 temperature" << std::endl;
|
||||
@ -700,7 +689,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<int32_t> tempRw3 = lp_var_t<int32_t>(objects::RW3, rws::TEMPERATURE_C);
|
||||
PoolReadGuard pg(&tempRw3, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read reaction wheel 3 temperature" << std::endl;
|
||||
@ -713,7 +701,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<int32_t> tempRw4 = lp_var_t<int32_t>(objects::RW4, rws::TEMPERATURE_C);
|
||||
PoolReadGuard pg(&tempRw4, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read reaction wheel 4 temperature" << std::endl;
|
||||
@ -726,8 +713,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> tempStartracker =
|
||||
lp_var_t<float>(objects::STAR_TRACKER, startracker::MCU_TEMPERATURE);
|
||||
PoolReadGuard pg(&tempStartracker, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read startracker temperature" << std::endl;
|
||||
@ -740,8 +725,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> tempSyrlinksPowerAmplifier =
|
||||
lp_var_t<float>(objects::SYRLINKS_HANDLER, syrlinks::TEMP_POWER_AMPLIFIER);
|
||||
PoolReadGuard pg(&tempSyrlinksPowerAmplifier, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read syrlinks power amplifier temperature"
|
||||
@ -755,8 +738,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> tempSyrlinksBasebandBoard =
|
||||
lp_var_t<float>(objects::SYRLINKS_HANDLER, syrlinks::TEMP_BASEBAND_BOARD);
|
||||
PoolReadGuard pg(&tempSyrlinksBasebandBoard, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read syrlinks baseband board temperature"
|
||||
@ -770,7 +751,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<int16_t> tempMgt = lp_var_t<int16_t>(objects::IMTQ_HANDLER, imtq::MCU_TEMPERATURE);
|
||||
PoolReadGuard pg(&tempMgt, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read MGT temperature" << std::endl;
|
||||
@ -783,8 +763,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_vec_t<float, 3> tempAcu =
|
||||
lp_vec_t<float, 3>(objects::ACU_HANDLER, ACU::pool::ACU_TEMPERATURES);
|
||||
PoolReadGuard pg(&tempAcu, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read ACU temperatures" << std::endl;
|
||||
@ -799,7 +777,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> tempPdu1 = lp_var_t<float>(objects::PDU1_HANDLER, PDU::pool::PDU_TEMPERATURE);
|
||||
PoolReadGuard pg(&tempPdu1, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read PDU1 temperature" << std::endl;
|
||||
@ -812,7 +789,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> tempPdu2 = lp_var_t<float>(objects::PDU2_HANDLER, PDU::pool::PDU_TEMPERATURE);
|
||||
PoolReadGuard pg(&tempPdu2, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read PDU2 temperature" << std::endl;
|
||||
@ -825,8 +801,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> temp1P60dock =
|
||||
lp_var_t<float>(objects::P60DOCK_HANDLER, P60Dock::pool::P60DOCK_TEMPERATURE_1);
|
||||
PoolReadGuard pg(&temp1P60dock, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read P60 dock temperature 1" << std::endl;
|
||||
@ -839,8 +813,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> temp2P60dock =
|
||||
lp_var_t<float>(objects::P60DOCK_HANDLER, P60Dock::pool::P60DOCK_TEMPERATURE_2);
|
||||
PoolReadGuard pg(&temp2P60dock, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read P60 dock temperature 2" << std::endl;
|
||||
@ -853,8 +825,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> tempGyro0 =
|
||||
lp_var_t<float>(objects::GYRO_0_ADIS_HANDLER, adis1650x::TEMPERATURE);
|
||||
PoolReadGuard pg(&tempGyro0, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read gyro 0 temperature" << std::endl;
|
||||
@ -867,7 +837,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> tempGyro1 = lp_var_t<float>(objects::GYRO_1_L3G_HANDLER, l3gd20h::TEMPERATURE);
|
||||
PoolReadGuard pg(&tempGyro1, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read gyro 1 temperature" << std::endl;
|
||||
@ -880,8 +849,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> tempGyro2 =
|
||||
lp_var_t<float>(objects::GYRO_2_ADIS_HANDLER, adis1650x::TEMPERATURE);
|
||||
PoolReadGuard pg(&tempGyro2, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read gyro 2 temperature" << std::endl;
|
||||
@ -894,7 +861,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> tempGyro3 = lp_var_t<float>(objects::GYRO_3_L3G_HANDLER, l3gd20h::TEMPERATURE);
|
||||
PoolReadGuard pg(&tempGyro3, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read gyro 3 temperature" << std::endl;
|
||||
@ -907,8 +873,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> tempMgm0 =
|
||||
lp_var_t<float>(objects::MGM_0_LIS3_HANDLER, mgmLis3::TEMPERATURE_CELCIUS);
|
||||
PoolReadGuard pg(&tempMgm0, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read MGM 0 temperature" << std::endl;
|
||||
@ -921,8 +885,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> tempMgm2 =
|
||||
lp_var_t<float>(objects::MGM_2_LIS3_HANDLER, mgmLis3::TEMPERATURE_CELCIUS);
|
||||
PoolReadGuard pg(&tempMgm2, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read MGM 2 temperature" << std::endl;
|
||||
@ -935,7 +897,6 @@ void ThermalController::copyDevices() {
|
||||
}
|
||||
|
||||
{
|
||||
lp_var_t<float> tempAdcPayloadPcdu = lp_var_t<float>(objects::PLPCDU_HANDLER, plpcdu::TEMP);
|
||||
PoolReadGuard pg(&tempAdcPayloadPcdu, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
|
||||
if (pg.getReadResult() != returnvalue::OK) {
|
||||
sif::warning << "ThermalController: Failed to read payload PCDU ADC temperature" << std::endl;
|
||||
|
@ -1,12 +1,22 @@
|
||||
#ifndef MISSION_CONTROLLER_THERMALCONTROLLER_H_
|
||||
#define MISSION_CONTROLLER_THERMALCONTROLLER_H_
|
||||
|
||||
#include <bsp_q7s/core/CoreDefinitions.h>
|
||||
#include <fsfw/controller/ExtendedControllerBase.h>
|
||||
#include <fsfw/devicehandlers/DeviceHandlerThermalSet.h>
|
||||
#include <fsfw/timemanager/Countdown.h>
|
||||
#include <fsfw_hal/devicehandlers/devicedefinitions/gyroL3gHelpers.h>
|
||||
#include <fsfw_hal/devicehandlers/devicedefinitions/mgmLis3Helpers.h>
|
||||
#include <linux/devices/devicedefinitions/StarTrackerDefinitions.h>
|
||||
#include <mission/controller/controllerdefinitions/ThermalControllerDefinitions.h>
|
||||
#include <mission/devices/devicedefinitions/BpxBatteryDefinitions.h>
|
||||
#include <mission/devices/devicedefinitions/Max31865Definitions.h>
|
||||
#include <mission/devices/devicedefinitions/SyrlinksDefinitions.h>
|
||||
#include <mission/devices/devicedefinitions/Tmp1075Definitions.h>
|
||||
#include <mission/devices/devicedefinitions/gyroAdisHelpers.h>
|
||||
#include <mission/devices/devicedefinitions/imtqHelpers.h>
|
||||
#include <mission/devices/devicedefinitions/payloadPcduDefinitions.h>
|
||||
#include <mission/devices/devicedefinitions/rwHelpers.h>
|
||||
#include <mission/devices/devicedefinitions/susMax1227Helpers.h>
|
||||
|
||||
#include <list>
|
||||
@ -125,6 +135,44 @@ class ThermalController : public ExtendedControllerBase {
|
||||
susMax1227::SusDataset susSet10;
|
||||
susMax1227::SusDataset susSet11;
|
||||
|
||||
lp_var_t<float> tempQ7s = lp_var_t<float>(objects::CORE_CONTROLLER, core::PoolIds::TEMPERATURE);
|
||||
lp_var_t<int16_t> battTemp1 =
|
||||
lp_var_t<int16_t>(objects::BPX_BATT_HANDLER, BpxBattery::BATT_TEMP_1);
|
||||
lp_var_t<int16_t> battTemp2 =
|
||||
lp_var_t<int16_t>(objects::BPX_BATT_HANDLER, BpxBattery::BATT_TEMP_2);
|
||||
lp_var_t<int16_t> battTemp3 =
|
||||
lp_var_t<int16_t>(objects::BPX_BATT_HANDLER, BpxBattery::BATT_TEMP_3);
|
||||
lp_var_t<int16_t> battTemp4 =
|
||||
lp_var_t<int16_t>(objects::BPX_BATT_HANDLER, BpxBattery::BATT_TEMP_4);
|
||||
lp_var_t<int32_t> tempRw1 = lp_var_t<int32_t>(objects::RW1, rws::TEMPERATURE_C);
|
||||
lp_var_t<int32_t> tempRw2 = lp_var_t<int32_t>(objects::RW2, rws::TEMPERATURE_C);
|
||||
lp_var_t<int32_t> tempRw3 = lp_var_t<int32_t>(objects::RW3, rws::TEMPERATURE_C);
|
||||
lp_var_t<int32_t> tempRw4 = lp_var_t<int32_t>(objects::RW4, rws::TEMPERATURE_C);
|
||||
lp_var_t<float> tempStartracker =
|
||||
lp_var_t<float>(objects::STAR_TRACKER, startracker::MCU_TEMPERATURE);
|
||||
lp_var_t<float> tempSyrlinksPowerAmplifier =
|
||||
lp_var_t<float>(objects::SYRLINKS_HANDLER, syrlinks::TEMP_POWER_AMPLIFIER);
|
||||
lp_var_t<float> tempSyrlinksBasebandBoard =
|
||||
lp_var_t<float>(objects::SYRLINKS_HANDLER, syrlinks::TEMP_BASEBAND_BOARD);
|
||||
lp_var_t<int16_t> tempMgt = lp_var_t<int16_t>(objects::IMTQ_HANDLER, imtq::MCU_TEMPERATURE);
|
||||
lp_vec_t<float, 3> tempAcu =
|
||||
lp_vec_t<float, 3>(objects::ACU_HANDLER, ACU::pool::ACU_TEMPERATURES);
|
||||
lp_var_t<float> tempPdu1 = lp_var_t<float>(objects::PDU1_HANDLER, PDU::pool::PDU_TEMPERATURE);
|
||||
lp_var_t<float> tempPdu2 = lp_var_t<float>(objects::PDU2_HANDLER, PDU::pool::PDU_TEMPERATURE);
|
||||
lp_var_t<float> temp1P60dock =
|
||||
lp_var_t<float>(objects::P60DOCK_HANDLER, P60Dock::pool::P60DOCK_TEMPERATURE_1);
|
||||
lp_var_t<float> temp2P60dock =
|
||||
lp_var_t<float>(objects::P60DOCK_HANDLER, P60Dock::pool::P60DOCK_TEMPERATURE_2);
|
||||
lp_var_t<float> tempGyro0 = lp_var_t<float>(objects::GYRO_0_ADIS_HANDLER, adis1650x::TEMPERATURE);
|
||||
lp_var_t<float> tempGyro1 = lp_var_t<float>(objects::GYRO_1_L3G_HANDLER, l3gd20h::TEMPERATURE);
|
||||
lp_var_t<float> tempGyro2 = lp_var_t<float>(objects::GYRO_2_ADIS_HANDLER, adis1650x::TEMPERATURE);
|
||||
lp_var_t<float> tempGyro3 = lp_var_t<float>(objects::GYRO_3_L3G_HANDLER, l3gd20h::TEMPERATURE);
|
||||
lp_var_t<float> tempMgm0 =
|
||||
lp_var_t<float>(objects::MGM_0_LIS3_HANDLER, mgmLis3::TEMPERATURE_CELCIUS);
|
||||
lp_var_t<float> tempMgm2 =
|
||||
lp_var_t<float>(objects::MGM_2_LIS3_HANDLER, mgmLis3::TEMPERATURE_CELCIUS);
|
||||
lp_var_t<float> tempAdcPayloadPcdu = lp_var_t<float>(objects::PLPCDU_HANDLER, plpcdu::TEMP);
|
||||
|
||||
// TempLimits
|
||||
TempLimits acsBoardLimits = TempLimits(-40.0, -40.0, 80.0, 85.0, 85.0);
|
||||
TempLimits mgtLimits = TempLimits(-40.0, -40.0, 65.0, 70.0, 70.0);
|
||||
|
@ -21,13 +21,15 @@
|
||||
ReturnValue_t pst::pstSyrlinks(FixedTimeslotTaskIF *thisSequence) {
|
||||
uint32_t length = thisSequence->getPeriodMs();
|
||||
|
||||
#if OBSW_ADD_SYRLINKS == 1
|
||||
thisSequence->addSlot(objects::SYRLINKS_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||
thisSequence->addSlot(objects::SYRLINKS_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE);
|
||||
thisSequence->addSlot(objects::SYRLINKS_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||
thisSequence->addSlot(objects::SYRLINKS_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||
thisSequence->addSlot(objects::SYRLINKS_HANDLER, length * 0.25, DeviceHandlerIF::SEND_READ);
|
||||
thisSequence->addSlot(objects::SYRLINKS_HANDLER, length * 0.25, DeviceHandlerIF::GET_READ);
|
||||
thisSequence->addSlot(objects::SYRLINKS_HANDLER, length * 0.4, DeviceHandlerIF::SEND_WRITE);
|
||||
thisSequence->addSlot(objects::SYRLINKS_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE);
|
||||
thisSequence->addSlot(objects::SYRLINKS_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ);
|
||||
thisSequence->addSlot(objects::SYRLINKS_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ);
|
||||
#endif
|
||||
thisSequence->addSlot(objects::SYRLINKS_HANDLER, length * 0.7, DeviceHandlerIF::SEND_READ);
|
||||
thisSequence->addSlot(objects::SYRLINKS_HANDLER, length * 0.7, DeviceHandlerIF::GET_READ);
|
||||
|
||||
static_cast<void>(length);
|
||||
|
||||
@ -318,11 +320,23 @@ ReturnValue_t pst::pstTcsAndAcs(FixedTimeslotTaskIF *thisSequence, AcsPstCfg cfg
|
||||
}
|
||||
|
||||
if (cfg.scheduleStr) {
|
||||
// 2 COM cycles for full PST for STR. The STR requests 2 packets types in NORMAL mode, this
|
||||
// ensures we always get an updated STR dataset for a regular normal mode cycle.
|
||||
thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
|
||||
thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::SEND_WRITE);
|
||||
thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::GET_WRITE);
|
||||
thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::SEND_READ);
|
||||
thisSequence->addSlot(objects::STAR_TRACKER, length * 0, DeviceHandlerIF::GET_READ);
|
||||
thisSequence->addSlot(objects::STAR_TRACKER, length * config::spiSched::SCHED_BLOCK_2_PERIOD,
|
||||
DeviceHandlerIF::SEND_READ);
|
||||
thisSequence->addSlot(objects::STAR_TRACKER, length * config::spiSched::SCHED_BLOCK_2_PERIOD,
|
||||
DeviceHandlerIF::GET_READ);
|
||||
thisSequence->addSlot(objects::STAR_TRACKER, length * config::spiSched::SCHED_BLOCK_2_PERIOD,
|
||||
DeviceHandlerIF::SEND_WRITE);
|
||||
thisSequence->addSlot(objects::STAR_TRACKER, length * config::spiSched::SCHED_BLOCK_2_PERIOD,
|
||||
DeviceHandlerIF::GET_WRITE);
|
||||
thisSequence->addSlot(objects::STAR_TRACKER, length * config::spiSched::SCHED_BLOCK_3_PERIOD,
|
||||
DeviceHandlerIF::SEND_READ);
|
||||
thisSequence->addSlot(objects::STAR_TRACKER, length * config::spiSched::SCHED_BLOCK_3_PERIOD,
|
||||
DeviceHandlerIF::GET_READ);
|
||||
}
|
||||
|
||||
bool enableAside = true;
|
||||
|
@ -10,7 +10,6 @@ enum class ParameterId : uint8_t { DATARATE = 0 };
|
||||
|
||||
static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::SYRLINKS;
|
||||
|
||||
static constexpr Event FDIR_REACTION_IGNORED = event::makeEvent(SUBSYSTEM_ID, 0, severity::MEDIUM);
|
||||
//! [EXPORT] : [COMMENT] Transmitter is on now. P1: Submode, P2: Current default datarate.
|
||||
static constexpr Event TX_ON = event::makeEvent(SUBSYSTEM_ID, 1, severity::INFO);
|
||||
//! [EXPORT] : [COMMENT] Transmitter is off now.
|
||||
|
@ -23,8 +23,7 @@ ReturnValue_t SyrlinksFdir::eventReceived(EventMessage* event) {
|
||||
case DeviceHandlerIF::DEVICE_WANTS_HARD_REBOOT:
|
||||
// We'll try a recovery as long as defined in MAX_REBOOT.
|
||||
// Might cause some AssemblyBase cycles, so keep number low.
|
||||
// handleRecovery(event->getEvent());
|
||||
triggerEvent(syrlinks::FDIR_REACTION_IGNORED, event->getEvent(), 0);
|
||||
handleRecovery(event->getEvent());
|
||||
break;
|
||||
case DeviceHandlerIF::DEVICE_INTERPRETING_REPLY_FAILED:
|
||||
case DeviceHandlerIF::DEVICE_READING_REPLY_FAILED:
|
||||
@ -33,8 +32,7 @@ ReturnValue_t SyrlinksFdir::eventReceived(EventMessage* event) {
|
||||
case DeviceHandlerIF::DEVICE_BUILDING_COMMAND_FAILED:
|
||||
// These faults all mean that there were stupid replies from a device.
|
||||
if (strangeReplyCount.incrementAndCheck()) {
|
||||
// handleRecovery(event->getEvent());
|
||||
triggerEvent(syrlinks::FDIR_REACTION_IGNORED, event->getEvent(), 0);
|
||||
handleRecovery(event->getEvent());
|
||||
}
|
||||
break;
|
||||
case DeviceHandlerIF::DEVICE_SENDING_COMMAND_FAILED:
|
||||
@ -48,7 +46,6 @@ ReturnValue_t SyrlinksFdir::eventReceived(EventMessage* event) {
|
||||
// else
|
||||
if (missedReplyCount.incrementAndCheck()) {
|
||||
handleRecovery(event->getEvent());
|
||||
// triggerEvent(syrlinks::FDIR_REACTION_IGNORED, event->getEvent(), 0);
|
||||
}
|
||||
break;
|
||||
case StorageManagerIF::GET_DATA_FAILED:
|
||||
@ -81,7 +78,6 @@ ReturnValue_t SyrlinksFdir::eventReceived(EventMessage* event) {
|
||||
case Fuse::POWER_BELOW_LOW_LIMIT:
|
||||
// Device might got stuck during boot, retry.
|
||||
handleRecovery(event->getEvent());
|
||||
triggerEvent(syrlinks::FDIR_REACTION_IGNORED, event->getEvent(), 0);
|
||||
break;
|
||||
//****Thermal*****
|
||||
case ThermalComponentIF::COMPONENT_TEMP_LOW:
|
||||
@ -113,14 +109,12 @@ void SyrlinksFdir::eventConfirmed(EventMessage* event) {
|
||||
case DeviceHandlerIF::DEVICE_REQUESTING_REPLY_FAILED:
|
||||
case DeviceHandlerIF::DEVICE_MISSED_REPLY:
|
||||
if (missedReplyCount.incrementAndCheck()) {
|
||||
// handleRecovery(event->getEvent());
|
||||
triggerEvent(syrlinks::FDIR_REACTION_IGNORED, event->getEvent(), 0);
|
||||
handleRecovery(event->getEvent());
|
||||
}
|
||||
break;
|
||||
case PowerSwitchIF::SWITCH_WENT_OFF:
|
||||
// This means the switch went off only for one device.
|
||||
// handleRecovery(event->getEvent());
|
||||
triggerEvent(syrlinks::FDIR_REACTION_IGNORED, event->getEvent(), 0);
|
||||
handleRecovery(event->getEvent());
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
|
@ -39,7 +39,6 @@ ReturnValue_t CcsdsIpCoreHandler::performOperation(uint8_t operationCode) {
|
||||
}
|
||||
|
||||
ReturnValue_t CcsdsIpCoreHandler::initialize() {
|
||||
|
||||
AcceptsTelecommandsIF* tcDistributor =
|
||||
ObjectManager::instance()->get<AcceptsTelecommandsIF>(tcDestination);
|
||||
if (tcDistributor == nullptr) {
|
||||
@ -207,6 +206,8 @@ ReturnValue_t CcsdsIpCoreHandler::executeAction(ActionId_t actionId, MessageQueu
|
||||
void CcsdsIpCoreHandler::updateLinkState() { linkState = LINK_UP; }
|
||||
|
||||
void CcsdsIpCoreHandler::enableTransmit() {
|
||||
// Reset PTME on each transmit enable.
|
||||
updateBatPriorityFromParam();
|
||||
#ifndef TE0720_1CFA
|
||||
gpioIF->pullHigh(ptmeGpios.enableTxClock);
|
||||
gpioIF->pullHigh(ptmeGpios.enableTxData);
|
||||
|
@ -153,7 +153,7 @@ class CcsdsIpCoreHandler : public SystemObject,
|
||||
PtmeConfig& ptmeConfig;
|
||||
PtmeGpios ptmeGpios;
|
||||
// BAT priority bit on by default to enable priority selection mode for the PTME.
|
||||
uint8_t batPriorityParam = 1;
|
||||
uint8_t batPriorityParam = 0;
|
||||
bool updateBatPriorityOnTxOff = false;
|
||||
|
||||
GpioIF* gpioIF = nullptr;
|
||||
|
@ -11,6 +11,9 @@ ReturnValue_t LiveTmTask::performOperation(uint8_t opCode) {
|
||||
while (true) {
|
||||
// The funnel tasks are scheduled here directly as well.
|
||||
ReturnValue_t result = channel.sendNextTm();
|
||||
if (result == DirectTmSinkIF::IS_BUSY) {
|
||||
sif::error << "Lost live TM, PAPB busy" << std::endl;
|
||||
}
|
||||
if (result == MessageQueueIF::EMPTY) {
|
||||
if (tmFunnelCd.hasTimedOut()) {
|
||||
pusFunnel.performOperation(0);
|
||||
|
@ -13,26 +13,32 @@ PersistentLogTmStoreTask::PersistentLogTmStoreTask(object_id_t objectId, Storage
|
||||
miscStoreContext(persTmStore::DUMP_MISC_STORE_DONE) {}
|
||||
|
||||
ReturnValue_t PersistentLogTmStoreTask::performOperation(uint8_t opCode) {
|
||||
bool someonesBusy = false;
|
||||
auto stateHandlingForStore = [&](bool storeIsBusy) {
|
||||
if (storeIsBusy) {
|
||||
someonesBusy = true;
|
||||
}
|
||||
if (fileHasSwapped) {
|
||||
someFileWasSwapped = fileHasSwapped;
|
||||
}
|
||||
};
|
||||
while (true) {
|
||||
if (not cyclicStoreCheck()) {
|
||||
continue;
|
||||
}
|
||||
bool someonesBusy = false;
|
||||
bool busy = false;
|
||||
busy = handleOneStore(stores.okStore, okStoreContext);
|
||||
if (busy) {
|
||||
someonesBusy = true;
|
||||
}
|
||||
busy = handleOneStore(stores.notOkStore, notOkStoreContext);
|
||||
if (busy) {
|
||||
someonesBusy = true;
|
||||
}
|
||||
busy = handleOneStore(stores.miscStore, miscStoreContext);
|
||||
if (busy) {
|
||||
someonesBusy = true;
|
||||
}
|
||||
someonesBusy = false;
|
||||
someFileWasSwapped = false;
|
||||
stateHandlingForStore(handleOneStore(stores.okStore, okStoreContext));
|
||||
stateHandlingForStore(handleOneStore(stores.notOkStore, notOkStoreContext));
|
||||
stateHandlingForStore(handleOneStore(stores.miscStore, miscStoreContext));
|
||||
if (not someonesBusy) {
|
||||
TaskFactory::delayTask(40);
|
||||
TaskFactory::delayTask(100);
|
||||
} else /* and graceDelayDuringDumping.hasTimedOut()*/ {
|
||||
if (someFileWasSwapped) {
|
||||
TaskFactory::delayTask(20);
|
||||
}
|
||||
// TaskFactory::delayTask(2);
|
||||
// graceDelayDuringDumping.resetTimer();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -32,6 +32,8 @@ class PersistentLogTmStoreTask : public TmStoreTaskBase, public ExecutableObject
|
||||
DumpContext notOkStoreContext;
|
||||
DumpContext miscStoreContext;
|
||||
Countdown tcHandlingCd = Countdown(400);
|
||||
Countdown graceDelayDuringDumping = Countdown(200);
|
||||
bool someFileWasSwapped = false;
|
||||
|
||||
bool initStoresIfPossible();
|
||||
};
|
||||
|
@ -17,7 +17,15 @@ ReturnValue_t PersistentSingleTmStoreTask::performOperation(uint8_t opCode) {
|
||||
}
|
||||
bool busy = handleOneStore(storeWithQueue, dumpContext);
|
||||
if (not busy) {
|
||||
TaskFactory::delayTask(40);
|
||||
TaskFactory::delayTask(100);
|
||||
} else {
|
||||
if (fileHasSwapped) {
|
||||
TaskFactory::delayTask(20);
|
||||
}
|
||||
// if (fileHasSwapped and graceDelayDuringDumping.hasTimedOut()) {
|
||||
// TaskFactory::delayTask(2);
|
||||
// graceDelayDuringDumping.resetTimer();
|
||||
// }
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -19,6 +19,7 @@ class PersistentSingleTmStoreTask : public TmStoreTaskBase, public ExecutableObj
|
||||
PersistentTmStoreWithTmQueue& storeWithQueue;
|
||||
DumpContext dumpContext;
|
||||
Countdown tcHandlingCd = Countdown(400);
|
||||
Countdown graceDelayDuringDumping = Countdown(100);
|
||||
|
||||
bool initStoresIfPossible();
|
||||
};
|
||||
|
@ -195,11 +195,7 @@ ReturnValue_t PersistentTmStore::startDumpFromUpTo(uint32_t fromUnixSeconds,
|
||||
dumpParams.fromUnixTime = fromUnixSeconds;
|
||||
dumpParams.untilUnixTime = upToUnixSeconds;
|
||||
state = State::DUMPING;
|
||||
if (loadNextDumpFile() == DUMP_DONE) {
|
||||
// State will be set inside the function loading the next file.
|
||||
return DUMP_DONE;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
return loadNextDumpFile();
|
||||
}
|
||||
|
||||
ReturnValue_t PersistentTmStore::loadNextDumpFile() {
|
||||
@ -218,7 +214,7 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() {
|
||||
}
|
||||
sif::debug << "Path: " << dumpParams.dirEntry.path() << std::endl;
|
||||
|
||||
// Can't even read CCSDS header.
|
||||
// File empty or can't even read CCSDS header.
|
||||
if (dumpParams.fileSize <= 6) {
|
||||
continue;
|
||||
}
|
||||
@ -247,14 +243,12 @@ ReturnValue_t PersistentTmStore::loadNextDumpFile() {
|
||||
static_cast<std::streamsize>(dumpParams.fileSize));
|
||||
// Increment iterator for next cycle.
|
||||
dumpParams.dirIter++;
|
||||
break;
|
||||
return returnvalue::OK;
|
||||
}
|
||||
}
|
||||
if (dumpParams.dirIter == directory_iterator()) {
|
||||
state = State::IDLE;
|
||||
return DUMP_DONE;
|
||||
}
|
||||
return returnvalue::OK;
|
||||
// Directory iterator was consumed and we are done.
|
||||
state = State::IDLE;
|
||||
return DUMP_DONE;
|
||||
}
|
||||
|
||||
ReturnValue_t PersistentTmStore::dumpNextPacket(DirectTmSinkIF& tmSink, size_t& dumpedLen,
|
||||
|
@ -25,10 +25,12 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store,
|
||||
// Dump TMs when applicable
|
||||
if (store.getState() == PersistentTmStore::State::DUMPING) {
|
||||
size_t dumpedLen = 0;
|
||||
bool fileHasSwapped;
|
||||
if (not channel.isBusy()) {
|
||||
tmSinkBusyCd.resetTimer();
|
||||
result = store.dumpNextPacket(channel, dumpedLen, fileHasSwapped);
|
||||
if (result == DirectTmSinkIF::IS_BUSY) {
|
||||
sif::warning << "Unexpected PAPB busy" << std::endl;
|
||||
}
|
||||
if ((result == PersistentTmStore::DUMP_DONE or result == returnvalue::OK) and dumpedLen > 0) {
|
||||
dumpContext.dumpedBytes += dumpedLen;
|
||||
dumpContext.numberOfDumpedPackets += 1;
|
||||
@ -43,6 +45,13 @@ bool TmStoreTaskBase::handleOneStore(PersistentTmStoreWithTmQueue& store,
|
||||
} else if (result == returnvalue::OK) {
|
||||
dumpsPerformed = true;
|
||||
}
|
||||
} else {
|
||||
dumpContext.ptmeBusyCounter++;
|
||||
if (dumpContext.ptmeBusyCounter == 50) {
|
||||
sif::warning << "PTME busy for longer period. Dumped length so far: "
|
||||
<< dumpContext.dumpedBytes << std::endl;
|
||||
dumpContext.ptmeBusyCounter = 0;
|
||||
}
|
||||
}
|
||||
if (cancelDumpCd.hasTimedOut() or tmSinkBusyCd.hasTimedOut()) {
|
||||
triggerEvent(persTmStore::DUMP_WAS_CANCELLED, store.getObjectId());
|
||||
|
@ -16,6 +16,7 @@ class TmStoreTaskBase : public SystemObject {
|
||||
const Event eventIfDone;
|
||||
uint32_t numberOfDumpedPackets = 0;
|
||||
uint32_t dumpedBytes = 0;
|
||||
uint32_t ptmeBusyCounter = 0;
|
||||
};
|
||||
|
||||
TmStoreTaskBase(object_id_t objectId, StorageManagerIF& ipcStore, VirtualChannel& channel,
|
||||
@ -45,6 +46,7 @@ class TmStoreTaskBase : public SystemObject {
|
||||
Countdown tmSinkBusyCd = Countdown(60 * 1000);
|
||||
VirtualChannel& channel;
|
||||
bool storesInitialized = false;
|
||||
bool fileHasSwapped = false;
|
||||
SdCardMountedIF& sdcMan;
|
||||
};
|
||||
|
||||
|
@ -25,4 +25,12 @@ uint8_t VirtualChannel::getVcid() const { return vcId; }
|
||||
|
||||
const char* VirtualChannel::getName() const { return vcName.c_str(); }
|
||||
|
||||
bool VirtualChannel::isBusy() const { return ptme.isBusy(vcId); }
|
||||
bool VirtualChannel::isBusy() const {
|
||||
// Data is discarded, so channel is not busy.
|
||||
if (linkStateProvider.load()) {
|
||||
return false;
|
||||
}
|
||||
return ptme.isBusy(vcId);
|
||||
}
|
||||
|
||||
void VirtualChannel::cancelTransfer() { ptme.cancelTransfer(vcId); }
|
||||
|
@ -28,6 +28,7 @@ class VirtualChannel : public SystemObject, public VirtualChannelIF {
|
||||
ReturnValue_t sendNextTm(const uint8_t* data, size_t size);
|
||||
bool isBusy() const override;
|
||||
ReturnValue_t write(const uint8_t* data, size_t size) override;
|
||||
void cancelTransfer() override;
|
||||
uint8_t getVcid() const;
|
||||
|
||||
const char* getName() const;
|
||||
|
@ -36,7 +36,10 @@ ReturnValue_t VirtualChannelWithQueue::sendNextTm() {
|
||||
return result;
|
||||
}
|
||||
|
||||
write(data, size);
|
||||
result = write(data, size);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
}
|
||||
tmStore.deleteData(storeId);
|
||||
if (result != returnvalue::OK) {
|
||||
return result;
|
||||
|
2
thirdparty/arcsec_star_tracker
vendored
2
thirdparty/arcsec_star_tracker
vendored
@ -1 +1 @@
|
||||
Subproject commit 42907c36c58e7133d3d3cbefbf96c1a8e35b60b7
|
||||
Subproject commit cbb3b24dc1993b727735fd63576088401ba351ec
|
2
tmtc
2
tmtc
@ -1 +1 @@
|
||||
Subproject commit c171654d2b18547249ee03ace3a4016e8837cf4a
|
||||
Subproject commit 93ad3ada7d4f351ae15209a6ffd668a61474ea68
|
Loading…
Reference in New Issue
Block a user