diff --git a/CHANGELOG.md b/CHANGELOG.md index 7016c40f..52b2d1a0 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -10,6 +10,19 @@ list yields a list of all related PRs for each release. # [unreleased] +## Changed + +- PLOC Supervisor: Changes baudrate to 921600 + +# [v1.17.0] 28.11.2022 + +## Added + +- PLOC Supervisor Update: Update SW to use newest PLOC SUPV version by TAS + PR 1: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/316 + PR 2: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/324 + PR 3: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/326 + # [v1.16.0] 18.11.2022 - It is now possible to compile Linux components for the hosted build conditionally diff --git a/CMakeLists.txt b/CMakeLists.txt index 64716301..5111b9ed 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -10,7 +10,7 @@ cmake_minimum_required(VERSION 3.13) set(OBSW_VERSION_MAJOR_IF_GIT_FAILS 1) -set(OBSW_VERSION_MINOR_IF_GIT_FAILS 16) +set(OBSW_VERSION_MINOR_IF_GIT_FAILS 17) set(OBSW_VERSION_REVISION_IF_GIT_FAILS 0) # set(CMAKE_VERBOSE TRUE) @@ -141,7 +141,7 @@ set(OBSW_ADD_TMP_DEVICES ${INIT_VAL} CACHE STRING "Add TMP devices") set(OBSW_ADD_GOMSPACE_PCDU - ${INIT_VAL} + 1 CACHE STRING "Add GomSpace PCDU modules") set(OBSW_ADD_RW ${INIT_VAL} @@ -296,6 +296,9 @@ if(TGT_BSP) else() # Required by FSFW library set(FSFW_CONFIG_PATH "${BSP_PATH}/fsfwconfig") + if(UNIX) + set(EIVE_ADD_LINUX_FILES ON) + endif() endif() # Configuration files diff --git a/README.md b/README.md index f68eb210..403189d6 100644 --- a/README.md +++ b/README.md @@ -1055,6 +1055,29 @@ Get fill count: xsc_scratch read | wc -c ``` +## Custom device names in Linux with the `udev` module + +You can assign custom device names using the Linux `udev` system. +This works by specifying a rules file inside the `/etc/udev/rules.d` folder +which creates a SYMLINK if certain device properties are true. + +Each rule is a new line inside a rules file. +For example, the rule + +```txt +SUBSYSTEM=="tty", ATTRS{interface}=="Dual RS232-HS", ATTRS{bInterfaceNumber}=="01", SYMLINK+="ploc_supv +``` + +Will create a symlink `/dev/ploc_supv` if a connected USB device has the +same `interface` and `bInterfaceNumber` properties as shown above. + +You can list the properties for a given connected device using `udevadm`. +For example, you can do this for a connected example device `/dev/ttyUSB0` +by using + +```txt +udevadm info -a /dev/ttyUSB0 +``` ## Using `system` when debugging diff --git a/bsp_hosted/CMakeLists.txt b/bsp_hosted/CMakeLists.txt index 2804977d..ec2016b4 100644 --- a/bsp_hosted/CMakeLists.txt +++ b/bsp_hosted/CMakeLists.txt @@ -1,4 +1,4 @@ -target_sources(${OBSW_NAME} PUBLIC InitMission.cpp main.cpp ObjectFactory.cpp) +target_sources(${OBSW_NAME} PUBLIC scheduling.cpp main.cpp ObjectFactory.cpp) add_subdirectory(fsfwconfig) add_subdirectory(boardconfig) diff --git a/bsp_hosted/InitMission.h b/bsp_hosted/InitMission.h deleted file mode 100644 index 507de592..00000000 --- a/bsp_hosted/InitMission.h +++ /dev/null @@ -1,9 +0,0 @@ -#ifndef BSP_LINUX_INITMISSION_H_ -#define BSP_LINUX_INITMISSION_H_ - -namespace initmission { -void initMission(); -void initTasks(); -}; // namespace initmission - -#endif /* BSP_LINUX_INITMISSION_H_ */ diff --git a/bsp_hosted/OBSWConfig.h.in b/bsp_hosted/OBSWConfig.h.in index 9c7a3f03..f234e795 100644 --- a/bsp_hosted/OBSWConfig.h.in +++ b/bsp_hosted/OBSWConfig.h.in @@ -24,6 +24,7 @@ #define OBSW_ADD_GPS_0 0 #define OBSW_ADD_GPS_1 0 #define OBSW_ADD_RW 0 +#define OBSW_DEBUG_TMP1075 0 #define OBSW_ADD_BPX_BATTERY_HANDLER 0 #define OBSW_ADD_RTD_DEVICES 0 #define OBSW_ADD_PL_PCDU 0 @@ -100,6 +101,13 @@ /*******************************************************************/ /** CMake Defines */ /*******************************************************************/ + +// Use TCP instead of UDP for the TMTC bridge. This allows using the TMTC client locally +// because UDP packets are not allowed in the VPN +// This will cause the OBSW to initialize the TMTC bridge responsible for exchanging data with the +// CCSDS IP Cores. +#define OBSW_USE_TMTC_TCP_BRIDGE 0 + #cmakedefine EIVE_BUILD_GPSD_GPS_HANDLER #cmakedefine LIBGPS_VERSION_MAJOR @LIBGPS_VERSION_MAJOR@ diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index a3c94fe1..6db37e93 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -1,16 +1,19 @@ #include "ObjectFactory.h" +#include #include #include #include #include #include #include -#include #include "OBSWConfig.h" +#include "devConf.h" #include "eive/definitions.h" +#include "fsfw/platform.h" #include "fsfw_tests/integration/task/TestTask.h" +#include "tmtc/pusIds.h" #if OBSW_USE_TMTC_TCP_BRIDGE == 0 #include "fsfw/osal/common/UdpTcPollingTask.h" @@ -47,12 +50,25 @@ #include "dummies/helpers.h" #include "mission/utility/GlobalConfigHandler.h" +#ifdef PLATFORM_UNIX +#include +#include + +#include "devices/gpioIds.h" +#include "fsfw_hal/linux/gpio/Gpio.h" +#include "linux/devices/ploc/PlocMPSoCHandler.h" +#include "linux/devices/ploc/PlocMPSoCHelper.h" +#include "linux/devices/ploc/PlocSupervisorHandler.h" +#include "linux/devices/ploc/PlocSupvUartMan.h" +#include "test/gpio/DummyGpioIF.h" +#endif + void Factory::setStaticFrameworkObjectIds() { PusServiceBase::PUS_DISTRIBUTOR = objects::PUS_PACKET_DISTRIBUTOR; - PusServiceBase::PACKET_DESTINATION = objects::TM_FUNNEL; + PusServiceBase::PACKET_DESTINATION = objects::PUS_TM_FUNNEL; CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; - CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; + CommandingServiceBase::defaultPacketDestination = objects::PUS_TM_FUNNEL; VerificationReporter::DEFAULT_RECEIVER = objects::PUS_SERVICE_1_VERIFICATION; } @@ -63,10 +79,36 @@ void ObjectFactory::produce(void* args) { CfdpTmFunnel* cfdpFunnel; ObjectFactory::produceGenericObjects(nullptr, &pusFunnel, &cfdpFunnel); + DummyGpioIF* dummyGpioIF = new DummyGpioIF(); + auto* dummySwitcher = new DummyPowerSwitcher(objects::PCDU_HANDLER, 18, 0); + static_cast(dummyGpioIF); +#ifdef PLATFORM_UNIX + new SerialComIF(objects::UART_COM_IF); +#if OBSW_ADD_PLOC_MPSOC == 1 + std::string mpscoDev = ""; + auto mpsocCookie = new UartCookie(objects::PLOC_MPSOC_HANDLER, mpscoDev, uart::PLOC_MPSOC_BAUD, + mpsoc::MAX_REPLY_SIZE, UartModes::NON_CANONICAL); + mpsocCookie->setNoFixedSizeReply(); + auto plocMpsocHelper = new PlocMPSoCHelper(objects::PLOC_MPSOC_HELPER); + new PlocMPSoCHandler(objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, mpsocCookie, + plocMpsocHelper, Gpio(gpioIds::ENABLE_MPSOC_UART, dummyGpioIF), + objects::PLOC_SUPERVISOR_HANDLER); +#endif /* OBSW_ADD_PLOC_MPSOC == 1 */ +#if OBSW_ADD_PLOC_SUPERVISOR == 1 + std::string plocSupvString = "/dev/ploc_supv"; + auto supervisorCookie = + new SerialCookie(objects::PLOC_SUPERVISOR_HANDLER, plocSupvString, uart::PLOC_SUPV_BAUD, + supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL); + supervisorCookie->setNoFixedSizeReply(); + auto supvHelper = new PlocSupvUartManager(objects::PLOC_SUPERVISOR_HELPER); + new PlocSupervisorHandler(objects::PLOC_SUPERVISOR_HANDLER, supervisorCookie, + Gpio(gpioIds::ENABLE_SUPV_UART, dummyGpioIF), pcdu::PDU1_CH6_PLOC_12V, + *supvHelper); +#endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */ +#endif + dummy::DummyCfg cfg; - dummy::createDummies(cfg); - new TemperatureSensorsDummy(); - new SusDummy(); + dummy::createDummies(cfg, *dummySwitcher); new ThermalController(objects::THERMAL_CONTROLLER); new TestTask(objects::TEST_TASK); } diff --git a/bsp_hosted/fsfwconfig/events/translateEvents.cpp b/bsp_hosted/fsfwconfig/events/translateEvents.cpp index fb9e1bf4..ac00745c 100644 --- a/bsp_hosted/fsfwconfig/events/translateEvents.cpp +++ b/bsp_hosted/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 83 translations. + * @brief Auto-generated event translation file. Contains 239 translations. * @details - * Generated on: 2021-05-17 19:49:55 + * Generated on: 2022-11-16 15:25:08 */ #include "translateEvents.h" @@ -34,6 +34,7 @@ const char *DEVICE_UNREQUESTED_REPLY_STRING = "DEVICE_UNREQUESTED_REPLY"; const char *INVALID_DEVICE_COMMAND_STRING = "INVALID_DEVICE_COMMAND"; const char *MONITORING_LIMIT_EXCEEDED_STRING = "MONITORING_LIMIT_EXCEEDED"; const char *MONITORING_AMBIGUOUS_STRING = "MONITORING_AMBIGUOUS"; +const char *DEVICE_WANTS_HARD_REBOOT_STRING = "DEVICE_WANTS_HARD_REBOOT"; const char *FUSE_CURRENT_HIGH_STRING = "FUSE_CURRENT_HIGH"; const char *FUSE_WENT_OFF_STRING = "FUSE_WENT_OFF"; const char *POWER_ABOVE_HIGH_LIMIT_STRING = "POWER_ABOVE_HIGH_LIMIT"; @@ -59,7 +60,6 @@ const char *MONITOR_CHANGED_STATE_STRING = "MONITOR_CHANGED_STATE"; const char *VALUE_BELOW_LOW_LIMIT_STRING = "VALUE_BELOW_LOW_LIMIT"; const char *VALUE_ABOVE_HIGH_LIMIT_STRING = "VALUE_ABOVE_HIGH_LIMIT"; const char *VALUE_OUT_OF_RANGE_STRING = "VALUE_OUT_OF_RANGE"; -const char *SWITCHING_TM_FAILED_STRING = "SWITCHING_TM_FAILED"; const char *CHANGING_MODE_STRING = "CHANGING_MODE"; const char *MODE_INFO_STRING = "MODE_INFO"; const char *FALLBACK_FAILED_STRING = "FALLBACK_FAILED"; @@ -75,6 +75,7 @@ const char *OVERWRITING_HEALTH_STRING = "OVERWRITING_HEALTH"; const char *TRYING_RECOVERY_STRING = "TRYING_RECOVERY"; const char *RECOVERY_STEP_STRING = "RECOVERY_STEP"; const char *RECOVERY_DONE_STRING = "RECOVERY_DONE"; +const char *HANDLE_PACKET_FAILED_STRING = "HANDLE_PACKET_FAILED"; const char *RF_AVAILABLE_STRING = "RF_AVAILABLE"; const char *RF_LOST_STRING = "RF_LOST"; const char *BIT_LOCK_STRING = "BIT_LOCK"; @@ -82,15 +83,166 @@ const char *BIT_LOCK_LOST_STRING = "BIT_LOCK_LOST"; const char *FRAME_PROCESSING_FAILED_STRING = "FRAME_PROCESSING_FAILED"; const char *CLOCK_SET_STRING = "CLOCK_SET"; const char *CLOCK_SET_FAILURE_STRING = "CLOCK_SET_FAILURE"; +const char *TC_DELETION_FAILED_STRING = "TC_DELETION_FAILED"; const char *TEST_STRING = "TEST"; const char *CHANGE_OF_SETUP_PARAMETER_STRING = "CHANGE_OF_SETUP_PARAMETER"; +const char *STORE_ERROR_STRING = "STORE_ERROR"; +const char *MSG_QUEUE_ERROR_STRING = "MSG_QUEUE_ERROR"; +const char *SERIALIZATION_ERROR_STRING = "SERIALIZATION_ERROR"; +const char *SWITCH_CMD_SENT_STRING = "SWITCH_CMD_SENT"; +const char *SWITCH_HAS_CHANGED_STRING = "SWITCH_HAS_CHANGED"; +const char *SWITCHING_Q7S_DENIED_STRING = "SWITCHING_Q7S_DENIED"; +const char *FDIR_REACTION_IGNORED_STRING = "FDIR_REACTION_IGNORED"; +const char *GPIO_PULL_HIGH_FAILED_STRING = "GPIO_PULL_HIGH_FAILED"; +const char *GPIO_PULL_LOW_FAILED_STRING = "GPIO_PULL_LOW_FAILED"; +const char *HEATER_WENT_ON_STRING = "HEATER_WENT_ON"; +const char *HEATER_WENT_OFF_STRING = "HEATER_WENT_OFF"; +const char *SWITCH_ALREADY_ON_STRING = "SWITCH_ALREADY_ON"; +const char *SWITCH_ALREADY_OFF_STRING = "SWITCH_ALREADY_OFF"; +const char *MAIN_SWITCH_TIMEOUT_STRING = "MAIN_SWITCH_TIMEOUT"; +const char *FAULTY_HEATER_WAS_ON_STRING = "FAULTY_HEATER_WAS_ON"; +const char *BURN_PHASE_START_STRING = "BURN_PHASE_START"; +const char *BURN_PHASE_DONE_STRING = "BURN_PHASE_DONE"; +const char *MAIN_SWITCH_ON_TIMEOUT_STRING = "MAIN_SWITCH_ON_TIMEOUT"; +const char *MAIN_SWITCH_OFF_TIMEOUT_STRING = "MAIN_SWITCH_OFF_TIMEOUT"; +const char *DEPL_SA1_GPIO_SWTICH_ON_FAILED_STRING = "DEPL_SA1_GPIO_SWTICH_ON_FAILED"; +const char *DEPL_SA2_GPIO_SWTICH_ON_FAILED_STRING = "DEPL_SA2_GPIO_SWTICH_ON_FAILED"; +const char *DEPL_SA1_GPIO_SWTICH_OFF_FAILED_STRING = "DEPL_SA1_GPIO_SWTICH_OFF_FAILED"; +const char *DEPL_SA2_GPIO_SWTICH_OFF_FAILED_STRING = "DEPL_SA2_GPIO_SWTICH_OFF_FAILED"; +const char *AUTONOMOUS_DEPLOYMENT_COMPLETED_STRING = "AUTONOMOUS_DEPLOYMENT_COMPLETED"; const char *MEMORY_READ_RPT_CRC_FAILURE_STRING = "MEMORY_READ_RPT_CRC_FAILURE"; const char *ACK_FAILURE_STRING = "ACK_FAILURE"; const char *EXE_FAILURE_STRING = "EXE_FAILURE"; -const char *CRC_FAILURE_EVENT_STRING = "CRC_FAILURE_EVENT"; +const char *MPSOC_HANDLER_CRC_FAILURE_STRING = "MPSOC_HANDLER_CRC_FAILURE"; +const char *MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH_STRING = "MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH"; +const char *MPSOC_SHUTDOWN_FAILED_STRING = "MPSOC_SHUTDOWN_FAILED"; +const char *SELF_TEST_I2C_FAILURE_STRING = "SELF_TEST_I2C_FAILURE"; +const char *SELF_TEST_SPI_FAILURE_STRING = "SELF_TEST_SPI_FAILURE"; +const char *SELF_TEST_ADC_FAILURE_STRING = "SELF_TEST_ADC_FAILURE"; +const char *SELF_TEST_PWM_FAILURE_STRING = "SELF_TEST_PWM_FAILURE"; +const char *SELF_TEST_TC_FAILURE_STRING = "SELF_TEST_TC_FAILURE"; +const char *SELF_TEST_MTM_RANGE_FAILURE_STRING = "SELF_TEST_MTM_RANGE_FAILURE"; +const char *SELF_TEST_COIL_CURRENT_FAILURE_STRING = "SELF_TEST_COIL_CURRENT_FAILURE"; +const char *INVALID_ERROR_BYTE_STRING = "INVALID_ERROR_BYTE"; +const char *ERROR_STATE_STRING = "ERROR_STATE"; +const char *RESET_OCCURED_STRING = "RESET_OCCURED"; +const char *BOOTING_FIRMWARE_FAILED_STRING = "BOOTING_FIRMWARE_FAILED"; +const char *BOOTING_BOOTLOADER_FAILED_STRING = "BOOTING_BOOTLOADER_FAILED"; +const char *SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING = "SUPV_MEMORY_READ_RPT_CRC_FAILURE"; +const char *SUPV_UNKNOWN_TM_STRING = "SUPV_UNKNOWN_TM"; +const char *SUPV_UNINIMPLEMENTED_TM_STRING = "SUPV_UNINIMPLEMENTED_TM"; +const char *SUPV_ACK_FAILURE_STRING = "SUPV_ACK_FAILURE"; +const char *SUPV_EXE_FAILURE_STRING = "SUPV_EXE_FAILURE"; +const char *SUPV_CRC_FAILURE_EVENT_STRING = "SUPV_CRC_FAILURE_EVENT"; +const char *SUPV_HELPER_EXECUTING_STRING = "SUPV_HELPER_EXECUTING"; +const char *SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING = "SUPV_MPSOC_SHUWDOWN_BUILD_FAILED"; +const char *SANITIZATION_FAILED_STRING = "SANITIZATION_FAILED"; +const char *MOUNTED_SD_CARD_STRING = "MOUNTED_SD_CARD"; +const char *SEND_MRAM_DUMP_FAILED_STRING = "SEND_MRAM_DUMP_FAILED"; +const char *MRAM_DUMP_FAILED_STRING = "MRAM_DUMP_FAILED"; +const char *MRAM_DUMP_FINISHED_STRING = "MRAM_DUMP_FINISHED"; +const char *INVALID_TC_FRAME_STRING = "INVALID_TC_FRAME"; +const char *INVALID_FAR_STRING = "INVALID_FAR"; +const char *CARRIER_LOCK_STRING = "CARRIER_LOCK"; +const char *BIT_LOCK_PDEC_STRING = "BIT_LOCK_PDEC"; +const char *LOST_CARRIER_LOCK_PDEC_STRING = "LOST_CARRIER_LOCK_PDEC"; +const char *LOST_BIT_LOCK_PDEC_STRING = "LOST_BIT_LOCK_PDEC"; +const char *POLL_ERROR_PDEC_STRING = "POLL_ERROR_PDEC"; +const char *IMAGE_UPLOAD_FAILED_STRING = "IMAGE_UPLOAD_FAILED"; +const char *IMAGE_DOWNLOAD_FAILED_STRING = "IMAGE_DOWNLOAD_FAILED"; +const char *IMAGE_UPLOAD_SUCCESSFUL_STRING = "IMAGE_UPLOAD_SUCCESSFUL"; +const char *IMAGE_DOWNLOAD_SUCCESSFUL_STRING = "IMAGE_DOWNLOAD_SUCCESSFUL"; +const char *FLASH_WRITE_SUCCESSFUL_STRING = "FLASH_WRITE_SUCCESSFUL"; +const char *FLASH_READ_SUCCESSFUL_STRING = "FLASH_READ_SUCCESSFUL"; +const char *FLASH_READ_FAILED_STRING = "FLASH_READ_FAILED"; +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_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"; +const char *STR_HELPER_SENDING_PACKET_FAILED_STRING = "STR_HELPER_SENDING_PACKET_FAILED"; +const char *STR_HELPER_REQUESTING_MSG_FAILED_STRING = "STR_HELPER_REQUESTING_MSG_FAILED"; +const char *MPSOC_FLASH_WRITE_FAILED_STRING = "MPSOC_FLASH_WRITE_FAILED"; +const char *MPSOC_FLASH_WRITE_SUCCESSFUL_STRING = "MPSOC_FLASH_WRITE_SUCCESSFUL"; +const char *MPSOC_SENDING_COMMAND_FAILED_STRING = "MPSOC_SENDING_COMMAND_FAILED"; +const char *MPSOC_HELPER_REQUESTING_REPLY_FAILED_STRING = "MPSOC_HELPER_REQUESTING_REPLY_FAILED"; +const char *MPSOC_HELPER_READING_REPLY_FAILED_STRING = "MPSOC_HELPER_READING_REPLY_FAILED"; +const char *MPSOC_MISSING_ACK_STRING = "MPSOC_MISSING_ACK"; +const char *MPSOC_MISSING_EXE_STRING = "MPSOC_MISSING_EXE"; +const char *MPSOC_ACK_FAILURE_REPORT_STRING = "MPSOC_ACK_FAILURE_REPORT"; +const char *MPSOC_EXE_FAILURE_REPORT_STRING = "MPSOC_EXE_FAILURE_REPORT"; +const char *MPSOC_ACK_INVALID_APID_STRING = "MPSOC_ACK_INVALID_APID"; +const char *MPSOC_EXE_INVALID_APID_STRING = "MPSOC_EXE_INVALID_APID"; +const char *MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING = "MPSOC_HELPER_SEQ_CNT_MISMATCH"; +const char *MPSOC_TM_SIZE_ERROR_STRING = "MPSOC_TM_SIZE_ERROR"; +const char *MPSOC_TM_CRC_MISSMATCH_STRING = "MPSOC_TM_CRC_MISSMATCH"; +const char *TRANSITION_BACK_TO_OFF_STRING = "TRANSITION_BACK_TO_OFF"; +const char *NEG_V_OUT_OF_BOUNDS_STRING = "NEG_V_OUT_OF_BOUNDS"; +const char *U_DRO_OUT_OF_BOUNDS_STRING = "U_DRO_OUT_OF_BOUNDS"; +const char *I_DRO_OUT_OF_BOUNDS_STRING = "I_DRO_OUT_OF_BOUNDS"; +const char *U_X8_OUT_OF_BOUNDS_STRING = "U_X8_OUT_OF_BOUNDS"; +const char *I_X8_OUT_OF_BOUNDS_STRING = "I_X8_OUT_OF_BOUNDS"; +const char *U_TX_OUT_OF_BOUNDS_STRING = "U_TX_OUT_OF_BOUNDS"; +const char *I_TX_OUT_OF_BOUNDS_STRING = "I_TX_OUT_OF_BOUNDS"; +const char *U_MPA_OUT_OF_BOUNDS_STRING = "U_MPA_OUT_OF_BOUNDS"; +const char *I_MPA_OUT_OF_BOUNDS_STRING = "I_MPA_OUT_OF_BOUNDS"; +const char *U_HPA_OUT_OF_BOUNDS_STRING = "U_HPA_OUT_OF_BOUNDS"; +const char *I_HPA_OUT_OF_BOUNDS_STRING = "I_HPA_OUT_OF_BOUNDS"; +const char *TRANSITION_OTHER_SIDE_FAILED_STRING = "TRANSITION_OTHER_SIDE_FAILED"; +const char *NOT_ENOUGH_DEVICES_DUAL_MODE_STRING = "NOT_ENOUGH_DEVICES_DUAL_MODE"; +const char *POWER_STATE_MACHINE_TIMEOUT_STRING = "POWER_STATE_MACHINE_TIMEOUT"; +const char *SIDE_SWITCH_TRANSITION_NOT_ALLOWED_STRING = "SIDE_SWITCH_TRANSITION_NOT_ALLOWED"; +const char *CHILDREN_LOST_MODE_STRING = "CHILDREN_LOST_MODE"; +const char *GPS_FIX_CHANGE_STRING = "GPS_FIX_CHANGE"; +const char *P60_BOOT_COUNT_STRING = "P60_BOOT_COUNT"; +const char *BATT_MODE_STRING = "BATT_MODE"; +const char *BATT_MODE_CHANGED_STRING = "BATT_MODE_CHANGED"; +const char *SUPV_UPDATE_FAILED_STRING = "SUPV_UPDATE_FAILED"; +const char *SUPV_UPDATE_SUCCESSFUL_STRING = "SUPV_UPDATE_SUCCESSFUL"; +const char *SUPV_CONTINUE_UPDATE_FAILED_STRING = "SUPV_CONTINUE_UPDATE_FAILED"; +const char *SUPV_CONTINUE_UPDATE_SUCCESSFUL_STRING = "SUPV_CONTINUE_UPDATE_SUCCESSFUL"; +const char *TERMINATED_UPDATE_PROCEDURE_STRING = "TERMINATED_UPDATE_PROCEDURE"; +const char *SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL_STRING = "SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL"; +const char *SUPV_EVENT_BUFFER_REQUEST_FAILED_STRING = "SUPV_EVENT_BUFFER_REQUEST_FAILED"; +const char *SUPV_EVENT_BUFFER_REQUEST_TERMINATED_STRING = "SUPV_EVENT_BUFFER_REQUEST_TERMINATED"; +const char *SUPV_MEM_CHECK_OK_STRING = "SUPV_MEM_CHECK_OK"; +const char *SUPV_MEM_CHECK_FAIL_STRING = "SUPV_MEM_CHECK_FAIL"; +const char *SUPV_SENDING_COMMAND_FAILED_STRING = "SUPV_SENDING_COMMAND_FAILED"; +const char *SUPV_HELPER_REQUESTING_REPLY_FAILED_STRING = "SUPV_HELPER_REQUESTING_REPLY_FAILED"; +const char *SUPV_HELPER_READING_REPLY_FAILED_STRING = "SUPV_HELPER_READING_REPLY_FAILED"; +const char *SUPV_MISSING_ACK_STRING = "SUPV_MISSING_ACK"; +const char *SUPV_MISSING_EXE_STRING = "SUPV_MISSING_EXE"; +const char *SUPV_ACK_FAILURE_REPORT_STRING = "SUPV_ACK_FAILURE_REPORT"; +const char *SUPV_EXE_FAILURE_REPORT_STRING = "SUPV_EXE_FAILURE_REPORT"; +const char *SUPV_ACK_INVALID_APID_STRING = "SUPV_ACK_INVALID_APID"; +const char *SUPV_EXE_INVALID_APID_STRING = "SUPV_EXE_INVALID_APID"; +const char *ACK_RECEPTION_FAILURE_STRING = "ACK_RECEPTION_FAILURE"; +const char *EXE_RECEPTION_FAILURE_STRING = "EXE_RECEPTION_FAILURE"; +const char *WRITE_MEMORY_FAILED_STRING = "WRITE_MEMORY_FAILED"; +const char *SUPV_REPLY_SIZE_MISSMATCH_STRING = "SUPV_REPLY_SIZE_MISSMATCH"; +const char *SUPV_REPLY_CRC_MISSMATCH_STRING = "SUPV_REPLY_CRC_MISSMATCH"; +const char *SUPV_UPDATE_PROGRESS_STRING = "SUPV_UPDATE_PROGRESS"; +const char *HDLC_FRAME_REMOVAL_ERROR_STRING = "HDLC_FRAME_REMOVAL_ERROR"; +const char *HDLC_CRC_ERROR_STRING = "HDLC_CRC_ERROR"; +const char *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; +const char *REBOOT_SW_STRING = "REBOOT_SW"; +const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED"; +const char *REBOOT_HW_STRING = "REBOOT_HW"; +const char *NO_SD_CARD_ACTIVE_STRING = "NO_SD_CARD_ACTIVE"; +const char *MISSING_PACKET_STRING = "MISSING_PACKET"; +const char *EXPERIMENT_TIMEDOUT_STRING = "EXPERIMENT_TIMEDOUT"; +const char *MULTI_PACKET_COMMAND_DONE_STRING = "MULTI_PACKET_COMMAND_DONE"; +const char *SET_CONFIGFILEVALUE_FAILED_STRING = "SET_CONFIGFILEVALUE_FAILED"; +const char *GET_CONFIGFILEVALUE_FAILED_STRING = "GET_CONFIGFILEVALUE_FAILED"; +const char *INSERT_CONFIGFILEVALUE_FAILED_STRING = "INSERT_CONFIGFILEVALUE_FAILED"; +const char *WRITE_CONFIGFILE_FAILED_STRING = "WRITE_CONFIGFILE_FAILED"; +const char *READ_CONFIGFILE_FAILED_STRING = "READ_CONFIGFILE_FAILED"; const char *translateEvents(Event event) { - switch ((event & 0xffff)) { + switch ((event & 0xFFFF)) { case (2200): return STORE_SEND_WRITE_FAILED_STRING; case (2201): @@ -149,6 +301,8 @@ const char *translateEvents(Event event) { return MONITORING_LIMIT_EXCEEDED_STRING; case (2810): return MONITORING_AMBIGUOUS_STRING; + case (2811): + return DEVICE_WANTS_HARD_REBOOT_STRING; case (4201): return FUSE_CURRENT_HIGH_STRING; case (4202): @@ -199,8 +353,6 @@ const char *translateEvents(Event event) { return VALUE_ABOVE_HIGH_LIMIT_STRING; case (7204): return VALUE_OUT_OF_RANGE_STRING; - case (7301): - return SWITCHING_TM_FAILED_STRING; case (7400): return CHANGING_MODE_STRING; case (7401): @@ -231,6 +383,8 @@ const char *translateEvents(Event event) { return RECOVERY_STEP_STRING; case (7512): return RECOVERY_DONE_STRING; + case (7600): + return HANDLE_PACKET_FAILED_STRING; case (7900): return RF_AVAILABLE_STRING; case (7901): @@ -245,18 +399,320 @@ const char *translateEvents(Event event) { return CLOCK_SET_STRING; case (8901): return CLOCK_SET_FAILURE_STRING; + case (9100): + return TC_DELETION_FAILED_STRING; case (9700): return TEST_STRING; case (10600): return CHANGE_OF_SETUP_PARAMETER_STRING; - case (11101): + case (10800): + return STORE_ERROR_STRING; + case (10801): + return MSG_QUEUE_ERROR_STRING; + case (10802): + return SERIALIZATION_ERROR_STRING; + case (11300): + return SWITCH_CMD_SENT_STRING; + case (11301): + return SWITCH_HAS_CHANGED_STRING; + case (11302): + return SWITCHING_Q7S_DENIED_STRING; + case (11303): + return FDIR_REACTION_IGNORED_STRING; + case (11400): + return GPIO_PULL_HIGH_FAILED_STRING; + case (11401): + return GPIO_PULL_LOW_FAILED_STRING; + case (11402): + return HEATER_WENT_ON_STRING; + case (11403): + return HEATER_WENT_OFF_STRING; + case (11404): + return SWITCH_ALREADY_ON_STRING; + case (11405): + return SWITCH_ALREADY_OFF_STRING; + case (11406): + return MAIN_SWITCH_TIMEOUT_STRING; + case (11407): + return FAULTY_HEATER_WAS_ON_STRING; + case (11500): + return BURN_PHASE_START_STRING; + case (11501): + return BURN_PHASE_DONE_STRING; + case (11502): + return MAIN_SWITCH_ON_TIMEOUT_STRING; + case (11503): + return MAIN_SWITCH_OFF_TIMEOUT_STRING; + case (11504): + return DEPL_SA1_GPIO_SWTICH_ON_FAILED_STRING; + case (11505): + return DEPL_SA2_GPIO_SWTICH_ON_FAILED_STRING; + case (11506): + return DEPL_SA1_GPIO_SWTICH_OFF_FAILED_STRING; + case (11507): + return DEPL_SA2_GPIO_SWTICH_OFF_FAILED_STRING; + case (11508): + return AUTONOMOUS_DEPLOYMENT_COMPLETED_STRING; + case (11601): return MEMORY_READ_RPT_CRC_FAILURE_STRING; - case (11102): + case (11602): return ACK_FAILURE_STRING; - case (11103): + case (11603): return EXE_FAILURE_STRING; - case (11104): - return CRC_FAILURE_EVENT_STRING; + case (11604): + return MPSOC_HANDLER_CRC_FAILURE_STRING; + case (11605): + return MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH_STRING; + case (11606): + return MPSOC_SHUTDOWN_FAILED_STRING; + case (11701): + return SELF_TEST_I2C_FAILURE_STRING; + case (11702): + return SELF_TEST_SPI_FAILURE_STRING; + case (11703): + return SELF_TEST_ADC_FAILURE_STRING; + case (11704): + return SELF_TEST_PWM_FAILURE_STRING; + case (11705): + return SELF_TEST_TC_FAILURE_STRING; + case (11706): + return SELF_TEST_MTM_RANGE_FAILURE_STRING; + case (11707): + return SELF_TEST_COIL_CURRENT_FAILURE_STRING; + case (11708): + return INVALID_ERROR_BYTE_STRING; + case (11801): + return ERROR_STATE_STRING; + case (11802): + return RESET_OCCURED_STRING; + case (11901): + return BOOTING_FIRMWARE_FAILED_STRING; + case (11902): + return BOOTING_BOOTLOADER_FAILED_STRING; + case (12001): + return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING; + case (12002): + return SUPV_UNKNOWN_TM_STRING; + case (12003): + return SUPV_UNINIMPLEMENTED_TM_STRING; + case (12004): + return SUPV_ACK_FAILURE_STRING; + case (12005): + return SUPV_EXE_FAILURE_STRING; + case (12006): + return SUPV_CRC_FAILURE_EVENT_STRING; + case (12007): + return SUPV_HELPER_EXECUTING_STRING; + case (12008): + return SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING; + case (12100): + return SANITIZATION_FAILED_STRING; + case (12101): + return MOUNTED_SD_CARD_STRING; + case (12300): + return SEND_MRAM_DUMP_FAILED_STRING; + case (12301): + return MRAM_DUMP_FAILED_STRING; + case (12302): + return MRAM_DUMP_FINISHED_STRING; + case (12401): + return INVALID_TC_FRAME_STRING; + case (12402): + return INVALID_FAR_STRING; + case (12403): + return CARRIER_LOCK_STRING; + case (12404): + return BIT_LOCK_PDEC_STRING; + case (12405): + return LOST_CARRIER_LOCK_PDEC_STRING; + case (12406): + return LOST_BIT_LOCK_PDEC_STRING; + case (12407): + return POLL_ERROR_PDEC_STRING; + case (12500): + return IMAGE_UPLOAD_FAILED_STRING; + case (12501): + return IMAGE_DOWNLOAD_FAILED_STRING; + case (12502): + return IMAGE_UPLOAD_SUCCESSFUL_STRING; + case (12503): + return IMAGE_DOWNLOAD_SUCCESSFUL_STRING; + case (12504): + return FLASH_WRITE_SUCCESSFUL_STRING; + case (12505): + return FLASH_READ_SUCCESSFUL_STRING; + case (12506): + return FLASH_READ_FAILED_STRING; + case (12507): + return FIRMWARE_UPDATE_SUCCESSFUL_STRING; + case (12508): + return FIRMWARE_UPDATE_FAILED_STRING; + case (12509): + return STR_HELPER_READING_REPLY_FAILED_STRING; + case (12510): + return STR_HELPER_COM_ERROR_STRING; + case (12511): + return STR_HELPER_NO_REPLY_STRING; + case (12512): + return STR_HELPER_DEC_ERROR_STRING; + case (12513): + return POSITION_MISMATCH_STRING; + case (12514): + return STR_HELPER_FILE_NOT_EXISTS_STRING; + case (12515): + return STR_HELPER_SENDING_PACKET_FAILED_STRING; + case (12516): + return STR_HELPER_REQUESTING_MSG_FAILED_STRING; + case (12600): + return MPSOC_FLASH_WRITE_FAILED_STRING; + case (12601): + return MPSOC_FLASH_WRITE_SUCCESSFUL_STRING; + case (12602): + return MPSOC_SENDING_COMMAND_FAILED_STRING; + case (12603): + return MPSOC_HELPER_REQUESTING_REPLY_FAILED_STRING; + case (12604): + return MPSOC_HELPER_READING_REPLY_FAILED_STRING; + case (12605): + return MPSOC_MISSING_ACK_STRING; + case (12606): + return MPSOC_MISSING_EXE_STRING; + case (12607): + return MPSOC_ACK_FAILURE_REPORT_STRING; + case (12608): + return MPSOC_EXE_FAILURE_REPORT_STRING; + case (12609): + return MPSOC_ACK_INVALID_APID_STRING; + case (12610): + return MPSOC_EXE_INVALID_APID_STRING; + case (12611): + return MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING; + case (12612): + return MPSOC_TM_SIZE_ERROR_STRING; + case (12613): + return MPSOC_TM_CRC_MISSMATCH_STRING; + case (12700): + return TRANSITION_BACK_TO_OFF_STRING; + case (12701): + return NEG_V_OUT_OF_BOUNDS_STRING; + case (12702): + return U_DRO_OUT_OF_BOUNDS_STRING; + case (12703): + return I_DRO_OUT_OF_BOUNDS_STRING; + case (12704): + return U_X8_OUT_OF_BOUNDS_STRING; + case (12705): + return I_X8_OUT_OF_BOUNDS_STRING; + case (12706): + return U_TX_OUT_OF_BOUNDS_STRING; + case (12707): + return I_TX_OUT_OF_BOUNDS_STRING; + case (12708): + return U_MPA_OUT_OF_BOUNDS_STRING; + case (12709): + return I_MPA_OUT_OF_BOUNDS_STRING; + case (12710): + return U_HPA_OUT_OF_BOUNDS_STRING; + case (12711): + return I_HPA_OUT_OF_BOUNDS_STRING; + case (12800): + return TRANSITION_OTHER_SIDE_FAILED_STRING; + case (12801): + return NOT_ENOUGH_DEVICES_DUAL_MODE_STRING; + case (12802): + return POWER_STATE_MACHINE_TIMEOUT_STRING; + case (12803): + return SIDE_SWITCH_TRANSITION_NOT_ALLOWED_STRING; + case (13000): + return CHILDREN_LOST_MODE_STRING; + case (13100): + return GPS_FIX_CHANGE_STRING; + case (13200): + return P60_BOOT_COUNT_STRING; + case (13201): + return BATT_MODE_STRING; + case (13202): + return BATT_MODE_CHANGED_STRING; + case (13600): + return SUPV_UPDATE_FAILED_STRING; + case (13601): + return SUPV_UPDATE_SUCCESSFUL_STRING; + case (13602): + return SUPV_CONTINUE_UPDATE_FAILED_STRING; + case (13603): + return SUPV_CONTINUE_UPDATE_SUCCESSFUL_STRING; + case (13604): + return TERMINATED_UPDATE_PROCEDURE_STRING; + case (13605): + return SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL_STRING; + case (13606): + return SUPV_EVENT_BUFFER_REQUEST_FAILED_STRING; + case (13607): + return SUPV_EVENT_BUFFER_REQUEST_TERMINATED_STRING; + case (13608): + return SUPV_MEM_CHECK_OK_STRING; + case (13609): + return SUPV_MEM_CHECK_FAIL_STRING; + case (13616): + return SUPV_SENDING_COMMAND_FAILED_STRING; + case (13617): + return SUPV_HELPER_REQUESTING_REPLY_FAILED_STRING; + case (13618): + return SUPV_HELPER_READING_REPLY_FAILED_STRING; + case (13619): + return SUPV_MISSING_ACK_STRING; + case (13620): + return SUPV_MISSING_EXE_STRING; + case (13621): + return SUPV_ACK_FAILURE_REPORT_STRING; + case (13622): + return SUPV_EXE_FAILURE_REPORT_STRING; + case (13623): + return SUPV_ACK_INVALID_APID_STRING; + case (13624): + return SUPV_EXE_INVALID_APID_STRING; + case (13625): + return ACK_RECEPTION_FAILURE_STRING; + case (13626): + return EXE_RECEPTION_FAILURE_STRING; + case (13627): + return WRITE_MEMORY_FAILED_STRING; + case (13628): + return SUPV_REPLY_SIZE_MISSMATCH_STRING; + case (13629): + return SUPV_REPLY_CRC_MISSMATCH_STRING; + case (13630): + return SUPV_UPDATE_PROGRESS_STRING; + case (13631): + return HDLC_FRAME_REMOVAL_ERROR_STRING; + case (13632): + return HDLC_CRC_ERROR_STRING; + case (13700): + return ALLOC_FAILURE_STRING; + case (13701): + return REBOOT_SW_STRING; + case (13702): + return REBOOT_MECHANISM_TRIGGERED_STRING; + case (13703): + return REBOOT_HW_STRING; + case (13704): + return NO_SD_CARD_ACTIVE_STRING; + case (13800): + return MISSING_PACKET_STRING; + case (13801): + return EXPERIMENT_TIMEDOUT_STRING; + case (13802): + return MULTI_PACKET_COMMAND_DONE_STRING; + case (13901): + return SET_CONFIGFILEVALUE_FAILED_STRING; + case (13902): + return GET_CONFIGFILEVALUE_FAILED_STRING; + case (13903): + return INSERT_CONFIGFILEVALUE_FAILED_STRING; + case (13904): + return WRITE_CONFIGFILE_FAILED_STRING; + case (13905): + return READ_CONFIGFILE_FAILED_STRING; default: return "UNKNOWN_EVENT"; } diff --git a/bsp_hosted/fsfwconfig/events/translateEvents.h b/bsp_hosted/fsfwconfig/events/translateEvents.h index a42d9b5a..99554317 100644 --- a/bsp_hosted/fsfwconfig/events/translateEvents.h +++ b/bsp_hosted/fsfwconfig/events/translateEvents.h @@ -1,8 +1,8 @@ #ifndef FSFWCONFIG_EVENTS_TRANSLATEEVENTS_H_ #define FSFWCONFIG_EVENTS_TRANSLATEEVENTS_H_ -#include +#include "fsfw/events/Event.h" -const char* translateEvents(Event event); +const char *translateEvents(Event event); #endif /* FSFWCONFIG_EVENTS_TRANSLATEEVENTS_H_ */ diff --git a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp index ee9cb057..4856c347 100644 --- a/bsp_hosted/fsfwconfig/objects/translateObjects.cpp +++ b/bsp_hosted/fsfwconfig/objects/translateObjects.cpp @@ -1,23 +1,105 @@ /** - * @brief Auto-generated object translation file. + * @brief Auto-generated object translation file. * @details - * Contains 31 translations. - * Generated on: 2021-05-17 19:12:49 + * Contains 148 translations. + * Generated on: 2022-11-15 17:44:20 */ #include "translateObjects.h" -#include "systemObjectList.h" - -const char *TEST_TASK_STRING = "TEST_TASK"; -const char *DUMMY_HANDLER_STRING = "DUMMY_HANDLER"; +const char *P60DOCK_TEST_TASK_STRING = "P60DOCK_TEST_TASK"; +const char *ACS_CONTROLLER_STRING = "ACS_CONTROLLER"; +const char *CORE_CONTROLLER_STRING = "CORE_CONTROLLER"; +const char *GLOBAL_JSON_CFG_STRING = "GLOBAL_JSON_CFG"; +const char *THERMAL_CONTROLLER_STRING = "THERMAL_CONTROLLER"; +const char *MGM_0_LIS3_HANDLER_STRING = "MGM_0_LIS3_HANDLER"; +const char *GYRO_0_ADIS_HANDLER_STRING = "GYRO_0_ADIS_HANDLER"; +const char *SUS_0_N_LOC_XFYFZM_PT_XF_STRING = "SUS_0_N_LOC_XFYFZM_PT_XF"; +const char *SUS_1_N_LOC_XBYFZM_PT_XB_STRING = "SUS_1_N_LOC_XBYFZM_PT_XB"; +const char *SUS_2_N_LOC_XFYBZB_PT_YB_STRING = "SUS_2_N_LOC_XFYBZB_PT_YB"; +const char *SUS_3_N_LOC_XFYBZF_PT_YF_STRING = "SUS_3_N_LOC_XFYBZF_PT_YF"; +const char *SUS_4_N_LOC_XMYFZF_PT_ZF_STRING = "SUS_4_N_LOC_XMYFZF_PT_ZF"; +const char *SUS_5_N_LOC_XFYMZB_PT_ZB_STRING = "SUS_5_N_LOC_XFYMZB_PT_ZB"; +const char *SUS_6_R_LOC_XFYBZM_PT_XF_STRING = "SUS_6_R_LOC_XFYBZM_PT_XF"; +const char *SUS_7_R_LOC_XBYBZM_PT_XB_STRING = "SUS_7_R_LOC_XBYBZM_PT_XB"; +const char *SUS_8_R_LOC_XBYBZB_PT_YB_STRING = "SUS_8_R_LOC_XBYBZB_PT_YB"; +const char *SUS_9_R_LOC_XBYBZB_PT_YF_STRING = "SUS_9_R_LOC_XBYBZB_PT_YF"; +const char *SUS_10_N_LOC_XMYBZF_PT_ZF_STRING = "SUS_10_N_LOC_XMYBZF_PT_ZF"; +const char *SUS_11_R_LOC_XBYMZB_PT_ZB_STRING = "SUS_11_R_LOC_XBYMZB_PT_ZB"; +const char *RW1_STRING = "RW1"; +const char *MGM_1_RM3100_HANDLER_STRING = "MGM_1_RM3100_HANDLER"; +const char *GYRO_1_L3G_HANDLER_STRING = "GYRO_1_L3G_HANDLER"; +const char *RW2_STRING = "RW2"; +const char *MGM_2_LIS3_HANDLER_STRING = "MGM_2_LIS3_HANDLER"; +const char *GYRO_2_ADIS_HANDLER_STRING = "GYRO_2_ADIS_HANDLER"; +const char *RW3_STRING = "RW3"; +const char *MGM_3_RM3100_HANDLER_STRING = "MGM_3_RM3100_HANDLER"; +const char *GYRO_3_L3G_HANDLER_STRING = "GYRO_3_L3G_HANDLER"; +const char *RW4_STRING = "RW4"; +const char *STAR_TRACKER_STRING = "STAR_TRACKER"; +const char *GPS_CONTROLLER_STRING = "GPS_CONTROLLER"; +const char *IMTQ_HANDLER_STRING = "IMTQ_HANDLER"; +const char *PCDU_HANDLER_STRING = "PCDU_HANDLER"; +const char *P60DOCK_HANDLER_STRING = "P60DOCK_HANDLER"; +const char *PDU1_HANDLER_STRING = "PDU1_HANDLER"; +const char *PDU2_HANDLER_STRING = "PDU2_HANDLER"; +const char *ACU_HANDLER_STRING = "ACU_HANDLER"; +const char *BPX_BATT_HANDLER_STRING = "BPX_BATT_HANDLER"; +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 *PLOC_MPSOC_HELPER_STRING = "PLOC_MPSOC_HELPER"; +const char *AXI_PTME_CONFIG_STRING = "AXI_PTME_CONFIG"; +const char *PTME_CONFIG_STRING = "PTME_CONFIG"; +const char *PLOC_MPSOC_HANDLER_STRING = "PLOC_MPSOC_HANDLER"; +const char *PLOC_SUPERVISOR_HANDLER_STRING = "PLOC_SUPERVISOR_HANDLER"; +const char *PLOC_SUPERVISOR_HELPER_STRING = "PLOC_SUPERVISOR_HELPER"; +const char *SCEX_STRING = "SCEX"; +const char *SOLAR_ARRAY_DEPL_HANDLER_STRING = "SOLAR_ARRAY_DEPL_HANDLER"; +const char *HEATER_HANDLER_STRING = "HEATER_HANDLER"; +const char *TMP1075_HANDLER_TCS_0_STRING = "TMP1075_HANDLER_TCS_0"; +const char *TMP1075_HANDLER_TCS_1_STRING = "TMP1075_HANDLER_TCS_1"; +const char *TMP1075_HANDLER_PLPCDU_0_STRING = "TMP1075_HANDLER_PLPCDU_0"; +const char *TMP1075_HANDLER_PLPCDU_1_STRING = "TMP1075_HANDLER_PLPCDU_1"; +const char *TMP1075_HANDLER_IF_BOARD_STRING = "TMP1075_HANDLER_IF_BOARD"; +const char *TMP1075_HANDLER_OBC_IF_BOARD_STRING = "TMP1075_HANDLER_OBC_IF_BOARD"; +const char *RTD_0_IC3_PLOC_HEATSPREADER_STRING = "RTD_0_IC3_PLOC_HEATSPREADER"; +const char *RTD_1_IC4_PLOC_MISSIONBOARD_STRING = "RTD_1_IC4_PLOC_MISSIONBOARD"; +const char *RTD_2_IC5_4K_CAMERA_STRING = "RTD_2_IC5_4K_CAMERA"; +const char *RTD_3_IC6_DAC_HEATSPREADER_STRING = "RTD_3_IC6_DAC_HEATSPREADER"; +const char *RTD_4_IC7_STARTRACKER_STRING = "RTD_4_IC7_STARTRACKER"; +const char *RTD_5_IC8_RW1_MX_MY_STRING = "RTD_5_IC8_RW1_MX_MY"; +const char *RTD_6_IC9_DRO_STRING = "RTD_6_IC9_DRO"; +const char *RTD_7_IC10_SCEX_STRING = "RTD_7_IC10_SCEX"; +const char *RTD_8_IC11_X8_STRING = "RTD_8_IC11_X8"; +const char *RTD_9_IC12_HPA_STRING = "RTD_9_IC12_HPA"; +const char *RTD_10_IC13_PL_TX_STRING = "RTD_10_IC13_PL_TX"; +const char *RTD_11_IC14_MPA_STRING = "RTD_11_IC14_MPA"; +const char *RTD_12_IC15_ACU_STRING = "RTD_12_IC15_ACU"; +const char *RTD_13_IC16_PLPCDU_HEATSPREADER_STRING = "RTD_13_IC16_PLPCDU_HEATSPREADER"; +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_HK_HANDLER_STRING = "SYRLINKS_HK_HANDLER"; const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF"; -const char *PUS_SERVICE_3_STRING = "PUS_SERVICE_3"; -const char *PUS_SERVICE_5_STRING = "PUS_SERVICE_5"; +const char *GPIO_IF_STRING = "GPIO_IF"; +const char *SCEX_UART_READER_STRING = "SCEX_UART_READER"; +const char *SPI_MAIN_COM_IF_STRING = "SPI_MAIN_COM_IF"; +const char *SPI_RW_COM_IF_STRING = "SPI_RW_COM_IF"; +const char *SPI_RTD_COM_IF_STRING = "SPI_RTD_COM_IF"; +const char *UART_COM_IF_STRING = "UART_COM_IF"; +const char *I2C_COM_IF_STRING = "I2C_COM_IF"; +const char *CSP_COM_IF_STRING = "CSP_COM_IF"; +const char *CCSDS_PACKET_DISTRIBUTOR_STRING = "CCSDS_PACKET_DISTRIBUTOR"; +const char *PUS_PACKET_DISTRIBUTOR_STRING = "PUS_PACKET_DISTRIBUTOR"; +const char *TMTC_BRIDGE_STRING = "TMTC_BRIDGE"; +const char *TMTC_POLLING_TASK_STRING = "TMTC_POLLING_TASK"; +const char *FILE_SYSTEM_HANDLER_STRING = "FILE_SYSTEM_HANDLER"; +const char *SDC_MANAGER_STRING = "SDC_MANAGER"; +const char *PTME_STRING = "PTME"; +const char *PDEC_HANDLER_STRING = "PDEC_HANDLER"; +const char *CCSDS_HANDLER_STRING = "CCSDS_HANDLER"; const char *PUS_SERVICE_6_STRING = "PUS_SERVICE_6"; -const char *PUS_SERVICE_8_STRING = "PUS_SERVICE_8"; -const char *PUS_SERVICE_23_STRING = "PUS_SERVICE_23"; -const char *PUS_SERVICE_201_STRING = "PUS_SERVICE_201"; -const char *TM_FUNNEL_STRING = "TM_FUNNEL"; const char *FSFW_OBJECTS_START_STRING = "FSFW_OBJECTS_START"; const char *PUS_SERVICE_1_VERIFICATION_STRING = "PUS_SERVICE_1_VERIFICATION"; const char *PUS_SERVICE_2_DEVICE_ACCESS_STRING = "PUS_SERVICE_2_DEVICE_ACCESS"; @@ -25,9 +107,12 @@ const char *PUS_SERVICE_3_HOUSEKEEPING_STRING = "PUS_SERVICE_3_HOUSEKEEPING"; const char *PUS_SERVICE_5_EVENT_REPORTING_STRING = "PUS_SERVICE_5_EVENT_REPORTING"; const char *PUS_SERVICE_8_FUNCTION_MGMT_STRING = "PUS_SERVICE_8_FUNCTION_MGMT"; const char *PUS_SERVICE_9_TIME_MGMT_STRING = "PUS_SERVICE_9_TIME_MGMT"; +const char *PUS_SERVICE_11_TC_SCHEDULER_STRING = "PUS_SERVICE_11_TC_SCHEDULER"; const char *PUS_SERVICE_17_TEST_STRING = "PUS_SERVICE_17_TEST"; const char *PUS_SERVICE_20_PARAMETERS_STRING = "PUS_SERVICE_20_PARAMETERS"; const char *PUS_SERVICE_200_MODE_MGMT_STRING = "PUS_SERVICE_200_MODE_MGMT"; +const char *PUS_SERVICE_201_HEALTH_STRING = "PUS_SERVICE_201_HEALTH"; +const char *CFDP_PACKET_DISTRIBUTOR_STRING = "CFDP_PACKET_DISTRIBUTOR"; const char *HEALTH_TABLE_STRING = "HEALTH_TABLE"; const char *MODE_STORE_STRING = "MODE_STORE"; const char *EVENT_MANAGER_STRING = "EVENT_MANAGER"; @@ -36,33 +121,230 @@ const char *TC_STORE_STRING = "TC_STORE"; const char *TM_STORE_STRING = "TM_STORE"; const char *IPC_STORE_STRING = "IPC_STORE"; const char *TIME_STAMPER_STRING = "TIME_STAMPER"; +const char *VERIFICATION_REPORTER_STRING = "VERIFICATION_REPORTER"; const char *FSFW_OBJECTS_END_STRING = "FSFW_OBJECTS_END"; +const char *SPI_TEST_STRING = "SPI_TEST"; +const char *UART_TEST_STRING = "UART_TEST"; +const char *I2C_TEST_STRING = "I2C_TEST"; +const char *DUMMY_COM_IF_STRING = "DUMMY_COM_IF"; +const char *DUMMY_HANDLER_STRING = "DUMMY_HANDLER"; const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE"; -const char *THERMAL_CONTROLLER_STRING = "THERMAL_CONTROLLER"; +const char *LIBGPIOD_TEST_STRING = "LIBGPIOD_TEST"; +const char *TEST_TASK_STRING = "TEST_TASK"; +const char *HEATER_0_PLOC_PROC_BRD_STRING = "HEATER_0_PLOC_PROC_BRD"; +const char *HEATER_1_PCDU_BRD_STRING = "HEATER_1_PCDU_BRD"; +const char *HEATER_2_ACS_BRD_STRING = "HEATER_2_ACS_BRD"; +const char *HEATER_3_OBC_BRD_STRING = "HEATER_3_OBC_BRD"; +const char *HEATER_4_CAMERA_STRING = "HEATER_4_CAMERA"; +const char *HEATER_5_STR_STRING = "HEATER_5_STR"; +const char *HEATER_6_DRO_STRING = "HEATER_6_DRO"; +const char *HEATER_7_HPA_STRING = "HEATER_7_HPA"; +const char *ACS_BOARD_ASS_STRING = "ACS_BOARD_ASS"; +const char *SUS_BOARD_ASS_STRING = "SUS_BOARD_ASS"; +const char *TCS_BOARD_ASS_STRING = "TCS_BOARD_ASS"; +const char *RW_ASS_STRING = "RW_ASS"; +const char *CAM_SWITCHER_STRING = "CAM_SWITCHER"; +const char *TM_FUNNEL_STRING = "TM_FUNNEL"; +const char *PUS_TM_FUNNEL_STRING = "PUS_TM_FUNNEL"; +const char *CFDP_TM_FUNNEL_STRING = "CFDP_TM_FUNNEL"; +const char *CFDP_HANDLER_STRING = "CFDP_HANDLER"; +const char *CFDP_DISTRIBUTOR_STRING = "CFDP_DISTRIBUTOR"; +const char *EIVE_SYSTEM_STRING = "EIVE_SYSTEM"; +const char *ACS_SUBSYSTEM_STRING = "ACS_SUBSYSTEM"; +const char *PL_SUBSYSTEM_STRING = "PL_SUBSYSTEM"; +const char *CCSDS_IP_CORE_BRIDGE_STRING = "CCSDS_IP_CORE_BRIDGE"; const char *NO_OBJECT_STRING = "NO_OBJECT"; const char *translateObject(object_id_t object) { switch ((object & 0xFFFFFFFF)) { - case 0x42694269: - return TEST_TASK_STRING; - case 0x4400AFFE: - return DUMMY_HANDLER_STRING; - case 0x49000001: + case 0x00005060: + return P60DOCK_TEST_TASK_STRING; + case 0x43000002: + return ACS_CONTROLLER_STRING; + case 0x43000003: + return CORE_CONTROLLER_STRING; + case 0x43000006: + return GLOBAL_JSON_CFG_STRING; + case 0x43400001: + return THERMAL_CONTROLLER_STRING; + case 0x44120006: + return MGM_0_LIS3_HANDLER_STRING; + case 0x44120010: + return GYRO_0_ADIS_HANDLER_STRING; + case 0x44120032: + return SUS_0_N_LOC_XFYFZM_PT_XF_STRING; + case 0x44120033: + return SUS_1_N_LOC_XBYFZM_PT_XB_STRING; + case 0x44120034: + return SUS_2_N_LOC_XFYBZB_PT_YB_STRING; + case 0x44120035: + return SUS_3_N_LOC_XFYBZF_PT_YF_STRING; + case 0x44120036: + return SUS_4_N_LOC_XMYFZF_PT_ZF_STRING; + case 0x44120037: + return SUS_5_N_LOC_XFYMZB_PT_ZB_STRING; + case 0x44120038: + return SUS_6_R_LOC_XFYBZM_PT_XF_STRING; + case 0x44120039: + return SUS_7_R_LOC_XBYBZM_PT_XB_STRING; + case 0x44120040: + return SUS_8_R_LOC_XBYBZB_PT_YB_STRING; + case 0x44120041: + return SUS_9_R_LOC_XBYBZB_PT_YF_STRING; + case 0x44120042: + return SUS_10_N_LOC_XMYBZF_PT_ZF_STRING; + case 0x44120043: + return SUS_11_R_LOC_XBYMZB_PT_ZB_STRING; + case 0x44120047: + return RW1_STRING; + case 0x44120107: + return MGM_1_RM3100_HANDLER_STRING; + case 0x44120111: + return GYRO_1_L3G_HANDLER_STRING; + case 0x44120148: + return RW2_STRING; + case 0x44120208: + return MGM_2_LIS3_HANDLER_STRING; + case 0x44120212: + return GYRO_2_ADIS_HANDLER_STRING; + case 0x44120249: + return RW3_STRING; + case 0x44120309: + return MGM_3_RM3100_HANDLER_STRING; + case 0x44120313: + return GYRO_3_L3G_HANDLER_STRING; + case 0x44120350: + return RW4_STRING; + case 0x44130001: + return STAR_TRACKER_STRING; + case 0x44130045: + return GPS_CONTROLLER_STRING; + case 0x44140014: + return IMTQ_HANDLER_STRING; + case 0x442000A1: + return PCDU_HANDLER_STRING; + case 0x44250000: + return P60DOCK_HANDLER_STRING; + case 0x44250001: + return PDU1_HANDLER_STRING; + case 0x44250002: + return PDU2_HANDLER_STRING; + case 0x44250003: + return ACU_HANDLER_STRING; + case 0x44260000: + return BPX_BATT_HANDLER_STRING; + case 0x44300000: + return PLPCDU_HANDLER_STRING; + case 0x443200A5: + return RAD_SENSOR_STRING; + case 0x44330000: + return PLOC_UPDATER_STRING; + case 0x44330001: + return PLOC_MEMORY_DUMPER_STRING; + case 0x44330002: + return STR_HELPER_STRING; + case 0x44330003: + return PLOC_MPSOC_HELPER_STRING; + case 0x44330004: + return AXI_PTME_CONFIG_STRING; + case 0x44330005: + return PTME_CONFIG_STRING; + case 0x44330015: + return PLOC_MPSOC_HANDLER_STRING; + case 0x44330016: + return PLOC_SUPERVISOR_HANDLER_STRING; + case 0x44330017: + return PLOC_SUPERVISOR_HELPER_STRING; + case 0x44330032: + return SCEX_STRING; + case 0x444100A2: + return SOLAR_ARRAY_DEPL_HANDLER_STRING; + case 0x444100A4: + return HEATER_HANDLER_STRING; + case 0x44420004: + return TMP1075_HANDLER_TCS_0_STRING; + case 0x44420005: + return TMP1075_HANDLER_TCS_1_STRING; + case 0x44420006: + return TMP1075_HANDLER_PLPCDU_0_STRING; + case 0x44420007: + return TMP1075_HANDLER_PLPCDU_1_STRING; + case 0x44420008: + return TMP1075_HANDLER_IF_BOARD_STRING; + case 0x44420009: + return TMP1075_HANDLER_OBC_IF_BOARD_STRING; + case 0x44420016: + return RTD_0_IC3_PLOC_HEATSPREADER_STRING; + case 0x44420017: + return RTD_1_IC4_PLOC_MISSIONBOARD_STRING; + case 0x44420018: + return RTD_2_IC5_4K_CAMERA_STRING; + case 0x44420019: + return RTD_3_IC6_DAC_HEATSPREADER_STRING; + case 0x44420020: + return RTD_4_IC7_STARTRACKER_STRING; + case 0x44420021: + return RTD_5_IC8_RW1_MX_MY_STRING; + case 0x44420022: + return RTD_6_IC9_DRO_STRING; + case 0x44420023: + return RTD_7_IC10_SCEX_STRING; + case 0x44420024: + return RTD_8_IC11_X8_STRING; + case 0x44420025: + return RTD_9_IC12_HPA_STRING; + case 0x44420026: + return RTD_10_IC13_PL_TX_STRING; + case 0x44420027: + return RTD_11_IC14_MPA_STRING; + case 0x44420028: + return RTD_12_IC15_ACU_STRING; + case 0x44420029: + return RTD_13_IC16_PLPCDU_HEATSPREADER_STRING; + case 0x44420030: + return RTD_14_IC17_TCS_BOARD_STRING; + case 0x44420031: + return RTD_15_IC18_IMTQ_STRING; + case 0x445300A3: + return SYRLINKS_HK_HANDLER_STRING; + case 0x49000000: return ARDUINO_COM_IF_STRING; - case 0x51000300: - return PUS_SERVICE_3_STRING; - case 0x51000400: - return PUS_SERVICE_5_STRING; + case 0x49010005: + return GPIO_IF_STRING; + case 0x49010006: + return SCEX_UART_READER_STRING; + case 0x49020004: + return SPI_MAIN_COM_IF_STRING; + case 0x49020005: + return SPI_RW_COM_IF_STRING; + case 0x49020006: + return SPI_RTD_COM_IF_STRING; + case 0x49030003: + return UART_COM_IF_STRING; + case 0x49040002: + return I2C_COM_IF_STRING; + case 0x49050001: + return CSP_COM_IF_STRING; + case 0x50000100: + return CCSDS_PACKET_DISTRIBUTOR_STRING; + case 0x50000200: + return PUS_PACKET_DISTRIBUTOR_STRING; + case 0x50000300: + return TMTC_BRIDGE_STRING; + case 0x50000400: + return TMTC_POLLING_TASK_STRING; + case 0x50000500: + return FILE_SYSTEM_HANDLER_STRING; + case 0x50000550: + return SDC_MANAGER_STRING; + case 0x50000600: + return PTME_STRING; + case 0x50000700: + return PDEC_HANDLER_STRING; + case 0x50000800: + return CCSDS_HANDLER_STRING; case 0x51000500: return PUS_SERVICE_6_STRING; - case 0x51000800: - return PUS_SERVICE_8_STRING; - case 0x51002300: - return PUS_SERVICE_23_STRING; - case 0x51020100: - return PUS_SERVICE_201_STRING; - case 0x52000002: - return TM_FUNNEL_STRING; case 0x53000000: return FSFW_OBJECTS_START_STRING; case 0x53000001: @@ -77,12 +359,18 @@ const char *translateObject(object_id_t object) { return PUS_SERVICE_8_FUNCTION_MGMT_STRING; case 0x53000009: return PUS_SERVICE_9_TIME_MGMT_STRING; + case 0x53000011: + return PUS_SERVICE_11_TC_SCHEDULER_STRING; case 0x53000017: return PUS_SERVICE_17_TEST_STRING; case 0x53000020: return PUS_SERVICE_20_PARAMETERS_STRING; case 0x53000200: return PUS_SERVICE_200_MODE_MGMT_STRING; + case 0x53000201: + return PUS_SERVICE_201_HEALTH_STRING; + case 0x53001000: + return CFDP_PACKET_DISTRIBUTOR_STRING; case 0x53010000: return HEALTH_TABLE_STRING; case 0x53010100: @@ -99,12 +387,70 @@ const char *translateObject(object_id_t object) { return IPC_STORE_STRING; case 0x53500010: return TIME_STAMPER_STRING; + case 0x53500020: + return VERIFICATION_REPORTER_STRING; case 0x53ffffff: return FSFW_OBJECTS_END_STRING; - case 0xCAFECAFE: + case 0x54000010: + return SPI_TEST_STRING; + case 0x54000020: + return UART_TEST_STRING; + case 0x54000030: + return I2C_TEST_STRING; + case 0x54000040: + return DUMMY_COM_IF_STRING; + case 0x5400AFFE: + return DUMMY_HANDLER_STRING; + case 0x5400CAFE: return DUMMY_INTERFACE_STRING; - case objects::THERMAL_CONTROLLER: - return THERMAL_CONTROLLER_STRING; + case 0x54123456: + return LIBGPIOD_TEST_STRING; + case 0x54694269: + return TEST_TASK_STRING; + case 0x60000000: + return HEATER_0_PLOC_PROC_BRD_STRING; + case 0x60000001: + return HEATER_1_PCDU_BRD_STRING; + case 0x60000002: + return HEATER_2_ACS_BRD_STRING; + case 0x60000003: + return HEATER_3_OBC_BRD_STRING; + case 0x60000004: + return HEATER_4_CAMERA_STRING; + case 0x60000005: + return HEATER_5_STR_STRING; + case 0x60000006: + return HEATER_6_DRO_STRING; + case 0x60000007: + return HEATER_7_HPA_STRING; + case 0x73000001: + return ACS_BOARD_ASS_STRING; + case 0x73000002: + return SUS_BOARD_ASS_STRING; + case 0x73000003: + return TCS_BOARD_ASS_STRING; + case 0x73000004: + return RW_ASS_STRING; + case 0x73000006: + return CAM_SWITCHER_STRING; + case 0x73000100: + return TM_FUNNEL_STRING; + case 0x73000101: + return PUS_TM_FUNNEL_STRING; + case 0x73000102: + return CFDP_TM_FUNNEL_STRING; + case 0x73000205: + return CFDP_HANDLER_STRING; + case 0x73000206: + return CFDP_DISTRIBUTOR_STRING; + case 0x73010000: + return EIVE_SYSTEM_STRING; + case 0x73010001: + return ACS_SUBSYSTEM_STRING; + case 0x73010002: + return PL_SUBSYSTEM_STRING; + case 0x73500000: + return CCSDS_IP_CORE_BRIDGE_STRING; case 0xFFFFFFFF: return NO_OBJECT_STRING; default: diff --git a/bsp_hosted/fsfwconfig/objects/translateObjects.h b/bsp_hosted/fsfwconfig/objects/translateObjects.h index dbf5b468..257912f4 100644 --- a/bsp_hosted/fsfwconfig/objects/translateObjects.h +++ b/bsp_hosted/fsfwconfig/objects/translateObjects.h @@ -3,6 +3,6 @@ #include -const char* translateObject(object_id_t object); +const char *translateObject(object_id_t object); #endif /* FSFWCONFIG_OBJECTS_TRANSLATEOBJECTS_H_ */ diff --git a/bsp_hosted/main.cpp b/bsp_hosted/main.cpp index e493c1c9..83f6777b 100644 --- a/bsp_hosted/main.cpp +++ b/bsp_hosted/main.cpp @@ -2,7 +2,6 @@ #include -#include "InitMission.h" #include "commonConfig.h" #include "fsfw/FSFWVersion.h" #include "fsfw/controller/ControllerBase.h" @@ -11,6 +10,7 @@ #include "fsfw/modes/ModeMessage.h" #include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/tasks/TaskFactory.h" +#include "scheduling.h" #ifdef WIN32 static const char* COMPILE_PRINTOUT = "Windows"; @@ -35,7 +35,7 @@ int main(void) { << " BSP HOSTED" << " --" << std::endl; - initmission::initMission(); + scheduling::initMission(); for (;;) { // suspend main thread by sleeping it. diff --git a/bsp_hosted/InitMission.cpp b/bsp_hosted/scheduling.cpp similarity index 70% rename from bsp_hosted/InitMission.cpp rename to bsp_hosted/scheduling.cpp index 4ee90f70..76a8f2e9 100644 --- a/bsp_hosted/InitMission.cpp +++ b/bsp_hosted/scheduling.cpp @@ -1,6 +1,5 @@ -#include "InitMission.h" +#include "linux/scheduling.h" -#include #include #include #include @@ -13,7 +12,9 @@ #include +#include "OBSWConfig.h" #include "ObjectFactory.h" +#include "scheduling.h" #ifdef LINUX ServiceInterfaceStream sif::debug("DEBUG"); @@ -29,7 +30,7 @@ ServiceInterfaceStream sif::error("ERROR", true, false, true); ObjectManagerIF* objectManager = nullptr; -void initmission::initMission() { +void scheduling::initMission() { sif::info << "Building global objects.." << std::endl; /* Instantiate global object manager and also create all objects */ ObjectManager::instance()->setObjectFactoryFunction(ObjectFactory::produce, nullptr); @@ -40,7 +41,7 @@ void initmission::initMission() { initTasks(); } -void initmission::initTasks() { +void scheduling::initTasks() { TaskFactory* factory = TaskFactory::instance(); if (factory == nullptr) { /* Should never happen ! */ @@ -53,28 +54,25 @@ void initmission::initTasks() { #endif /* TMTC Distribution */ - PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask( - "DIST", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); - ReturnValue_t result = tmTcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR); + PeriodicTaskIF* tmtcDistributor = factory->createPeriodicTask( + "DIST", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); + ReturnValue_t result = tmtcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR); if (result != returnvalue::OK) { sif::error << "Object add component failed" << std::endl; } - result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); + result = tmtcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); if (result != returnvalue::OK) { sif::error << "Object add component failed" << std::endl; } - result = tmTcDistributor->addComponent(objects::TM_FUNNEL); + result = tmtcDistributor->addComponent(objects::TM_FUNNEL); if (result != returnvalue::OK) { sif::error << "Object add component failed" << std::endl; } - - /* UDP bridge */ - PeriodicTaskIF* tmtcBridgeTask = factory->createPeriodicTask( - "TMTC_UNIX_BRIDGE", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); - result = tmtcBridgeTask->addComponent(objects::TMTC_BRIDGE); + result = tmtcDistributor->addComponent(objects::TMTC_BRIDGE); if (result != returnvalue::OK) { sif::error << "Add component UDP Unix Bridge failed" << std::endl; } + PeriodicTaskIF* tmtcPollingTask = factory->createPeriodicTask( "UDP_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); result = tmtcPollingTask->addComponent(objects::TMTC_POLLING_TASK); @@ -94,69 +92,69 @@ void initmission::initTasks() { "EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); result = eventHandling->addComponent(objects::EVENT_MANAGER); if (result != returnvalue::OK) { - initmission::printAddObjectError("EVENT_MNGR", objects::EVENT_MANAGER); + scheduling::printAddObjectError("EVENT_MNGR", objects::EVENT_MANAGER); } result = eventHandling->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS5", objects::PUS_SERVICE_5_EVENT_REPORTING); + scheduling::printAddObjectError("PUS5", objects::PUS_SERVICE_5_EVENT_REPORTING); } PeriodicTaskIF* pusHighPrio = factory->createPeriodicTask( "PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS2", objects::PUS_SERVICE_2_DEVICE_ACCESS); + scheduling::printAddObjectError("PUS2", objects::PUS_SERVICE_2_DEVICE_ACCESS); } result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT); + scheduling::printAddObjectError("PUS9", objects::PUS_SERVICE_9_TIME_MGMT); } result = pusHighPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS3", objects::PUS_SERVICE_3_HOUSEKEEPING); + scheduling::printAddObjectError("PUS3", objects::PUS_SERVICE_3_HOUSEKEEPING); } PeriodicTaskIF* pusMedPrio = factory->createPeriodicTask( "PUS_MED_PRIO", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.8, missedDeadlineFunc); result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS8", objects::PUS_SERVICE_8_FUNCTION_MGMT); + scheduling::printAddObjectError("PUS8", objects::PUS_SERVICE_8_FUNCTION_MGMT); } result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS200", objects::PUS_SERVICE_200_MODE_MGMT); + scheduling::printAddObjectError("PUS200", objects::PUS_SERVICE_200_MODE_MGMT); } result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS); + scheduling::printAddObjectError("PUS20", objects::PUS_SERVICE_20_PARAMETERS); } PeriodicTaskIF* pusLowPrio = factory->createPeriodicTask( "PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc); result = pusLowPrio->addComponent(objects::PUS_SERVICE_17_TEST); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST); + scheduling::printAddObjectError("PUS17", objects::PUS_SERVICE_17_TEST); } PeriodicTaskIF* thermalTask = factory->createPeriodicTask( "THERMAL_CTL_TASK", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc); result = thermalTask->addComponent(objects::RTD_0_IC3_PLOC_HEATSPREADER); if (result != returnvalue::OK) { - initmission::printAddObjectError("RTD_0_dummy", objects::RTD_0_IC3_PLOC_HEATSPREADER); + scheduling::printAddObjectError("RTD_0_dummy", objects::RTD_0_IC3_PLOC_HEATSPREADER); } result = thermalTask->addComponent(objects::SUS_0_N_LOC_XFYFZM_PT_XF); if (result != returnvalue::OK) { - initmission::printAddObjectError("SUS_0_dummy", objects::SUS_0_N_LOC_XFYFZM_PT_XF); + scheduling::printAddObjectError("SUS_0_dummy", objects::SUS_0_N_LOC_XFYFZM_PT_XF); } result = thermalTask->addComponent(objects::CORE_CONTROLLER); if (result != returnvalue::OK) { - initmission::printAddObjectError("Core controller dummy", objects::CORE_CONTROLLER); + scheduling::printAddObjectError("Core controller dummy", objects::CORE_CONTROLLER); } result = thermalTask->addComponent(objects::THERMAL_CONTROLLER); if (result != returnvalue::OK) { - initmission::printAddObjectError("THERMAL_CONTROLLER", objects::THERMAL_CONTROLLER); + scheduling::printAddObjectError("THERMAL_CONTROLLER", objects::THERMAL_CONTROLLER); } FixedTimeslotTaskIF* pstTask = factory->createFixedTimeslotTask( @@ -166,16 +164,27 @@ void initmission::initTasks() { sif::error << "Failed to add dummy pst to fixed timeslot task" << std::endl; } +#if OBSW_ADD_PLOC_SUPERVISOR == 1 + PeriodicTaskIF* supvHelperTask = factory->createPeriodicTask( + "PLOC_SUPV_HELPER", 20, 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); + } +#endif /* OBSW_ADD_PLOC_SUPERVISOR */ + + PeriodicTaskIF* plTask = factory->createPeriodicTask( + "PL_TASK", 25, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc); + scheduling::addMpsocSupvHandlers(plTask); #if OBSW_ADD_TEST_CODE == 1 result = testTask->addComponent(objects::TEST_TASK); if (result != returnvalue::OK) { - initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK); + scheduling::printAddObjectError("TEST_TASK", objects::TEST_TASK); } #endif /* OBSW_ADD_TEST_CODE == 1 */ sif::info << "Starting tasks.." << std::endl; - tmTcDistributor->startTask(); - tmtcBridgeTask->startTask(); + tmtcDistributor->startTask(); tmtcPollingTask->startTask(); pusVerification->startTask(); @@ -186,6 +195,12 @@ void initmission::initTasks() { pstTask->startTask(); thermalTask->startTask(); +#if OBSW_ADD_PLOC_SUPERVISOR == 1 + supvHelperTask->startTask(); +#endif +#if OBSW_ADD_PLOC_SUPERVISOR == 1 || OBSW_ADD_PLOC_MPSOC == 1 + plTask->startTask(); +#endif #if OBSW_ADD_TEST_CODE == 1 testTask->startTask(); diff --git a/bsp_hosted/scheduling.h b/bsp_hosted/scheduling.h new file mode 100644 index 00000000..2a2f32a0 --- /dev/null +++ b/bsp_hosted/scheduling.h @@ -0,0 +1,6 @@ +#pragma once + +namespace scheduling { +void initMission(); +void initTasks(); +}; // namespace scheduling diff --git a/bsp_q7s/OBSWConfig.h.in b/bsp_q7s/OBSWConfig.h.in index 499d8e6b..5cde824d 100644 --- a/bsp_q7s/OBSWConfig.h.in +++ b/bsp_q7s/OBSWConfig.h.in @@ -119,6 +119,13 @@ /*******************************************************************/ /** CMake Defines */ /*******************************************************************/ + +// Use TCP instead of UDP for the TMTC bridge. This allows using the TMTC client locally +// because UDP packets are not allowed in the VPN +// This will cause the OBSW to initialize the TMTC bridge responsible for exchanging data with the +// CCSDS IP Cores. +#define OBSW_USE_TMTC_TCP_BRIDGE 1 + #cmakedefine EIVE_BUILD_GPSD_GPS_HANDLER #cmakedefine LIBGPS_VERSION_MAJOR @LIBGPS_VERSION_MAJOR@ diff --git a/bsp_q7s/core/CMakeLists.txt b/bsp_q7s/core/CMakeLists.txt index b4050d73..15d361fd 100644 --- a/bsp_q7s/core/CMakeLists.txt +++ b/bsp_q7s/core/CMakeLists.txt @@ -1,4 +1,4 @@ -target_sources(${OBSW_NAME} PRIVATE CoreController.cpp InitMission.cpp +target_sources(${OBSW_NAME} PRIVATE CoreController.cpp scheduling.cpp ObjectFactory.cpp) -target_sources(${SIMPLE_OBSW_NAME} PRIVATE InitMission.cpp) +target_sources(${SIMPLE_OBSW_NAME} PRIVATE scheduling.cpp) diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index fc9240a0..85157e66 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -600,7 +600,6 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwit auto* camSwitcher = new CamSwitcher(objects::CAM_SWITCHER, pwrSwitch, pcdu::PDU2_CH8_PAYLOAD_CAMERA); camSwitcher->connectModeTreeParent(satsystem::pl::SUBSYSTEM); - // camSwitcher-> #if OBSW_ADD_PLOC_MPSOC == 1 consumer << "0x" << std::hex << objects::PLOC_MPSOC_HANDLER; auto gpioConfigMPSoC = new GpiodRegularByLineName(q7s::gpioNames::ENABLE_MPSOC_UART, @@ -629,10 +628,10 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwit new SerialCookie(objects::PLOC_SUPERVISOR_HANDLER, q7s::UART_PLOC_SUPERVSIOR_DEV, uart::PLOC_SUPV_BAUD, supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL); supervisorCookie->setNoFixedSizeReply(); - auto supvHelper = new PlocSupvHelper(objects::PLOC_SUPERVISOR_HELPER); - auto* supvHandler = new PlocSupervisorHandler( - objects::PLOC_SUPERVISOR_HANDLER, objects::UART_COM_IF, supervisorCookie, - Gpio(gpioIds::ENABLE_SUPV_UART, gpioComIF), pcdu::PDU1_CH6_PLOC_12V, supvHelper); + auto supvHelper = new PlocSupvUartManager(objects::PLOC_SUPERVISOR_HELPER); + auto* supvHandler = new PlocSupervisorHandler(objects::PLOC_SUPERVISOR_HANDLER, supervisorCookie, + Gpio(gpioIds::ENABLE_SUPV_UART, gpioComIF), + pcdu::PDU1_CH6_PLOC_12V, *supvHelper); supvHandler->connectModeTreeParent(satsystem::pl::SUBSYSTEM); #endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */ static_cast(consumer); diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/scheduling.cpp similarity index 79% rename from bsp_q7s/core/InitMission.cpp rename to bsp_q7s/core/scheduling.cpp index bbeaded8..f07eda32 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/scheduling.cpp @@ -1,7 +1,7 @@ -#include "bsp_q7s/core/InitMission.h" +#include "scheduling.h" #include -#include +#include #include #include @@ -35,13 +35,13 @@ ServiceInterfaceStream sif::error("ERROR", true, false, true); ObjectManagerIF* objectManager = nullptr; -void initmission::initMission() { +void scheduling::initMission() { sif::info << "Building global objects.." << std::endl; try { /* Instantiate global object manager and also create all objects */ ObjectManager::instance()->setObjectFactoryFunction(ObjectFactory::produce, nullptr); } catch (const std::invalid_argument& e) { - sif::error << "initmission::initMission: Object Construction failed with an " + sif::error << "scheduling::initMission: Object Construction failed with an " "invalid argument: " << e.what(); std::exit(1); @@ -54,7 +54,7 @@ void initmission::initMission() { initTasks(); } -void initmission::initTasks() { +void scheduling::initTasks() { TaskFactory* factory = TaskFactory::instance(); ReturnValue_t result = returnvalue::OK; if (factory == nullptr) { @@ -74,7 +74,7 @@ void initmission::initTasks() { "SOLAR_ARRAY_DEPL", 65, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc); result = solarArrayDeplTask->addComponent(objects::SOLAR_ARRAY_DEPL_HANDLER); if (result != returnvalue::OK) { - initmission::printAddObjectError("SOLAR_ARRAY_DEPL", objects::SOLAR_ARRAY_DEPL_HANDLER); + scheduling::printAddObjectError("SOLAR_ARRAY_DEPL", objects::SOLAR_ARRAY_DEPL_HANDLER); } #endif @@ -82,11 +82,11 @@ void initmission::initTasks() { "CORE_CTRL", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc); result = sysTask->addComponent(objects::CORE_CONTROLLER); if (result != returnvalue::OK) { - initmission::printAddObjectError("CORE_CTRL", objects::CORE_CONTROLLER); + scheduling::printAddObjectError("CORE_CTRL", objects::CORE_CONTROLLER); } result = sysTask->addComponent(objects::PL_SUBSYSTEM); if (result != returnvalue::OK) { - initmission::printAddObjectError("PL_SUBSYSTEM", objects::PL_SUBSYSTEM); + scheduling::printAddObjectError("PL_SUBSYSTEM", objects::PL_SUBSYSTEM); } /* TMTC Distribution */ @@ -95,24 +95,24 @@ void initmission::initTasks() { #if OBSW_ADD_TCPIP_BRIDGE == 1 result = tmTcDistributor->addComponent(objects::TMTC_BRIDGE); if (result != returnvalue::OK) { - initmission::printAddObjectError("TMTC_BRIDGE", objects::TMTC_BRIDGE); + scheduling::printAddObjectError("TMTC_BRIDGE", objects::TMTC_BRIDGE); } #endif result = tmTcDistributor->addComponent(objects::CCSDS_PACKET_DISTRIBUTOR); if (result != returnvalue::OK) { - initmission::printAddObjectError("CCSDS_DISTRIB", objects::CCSDS_PACKET_DISTRIBUTOR); + scheduling::printAddObjectError("CCSDS_DISTRIB", objects::CCSDS_PACKET_DISTRIBUTOR); } result = tmTcDistributor->addComponent(objects::PUS_PACKET_DISTRIBUTOR); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS_PACKET_DISTRIB", objects::PUS_PACKET_DISTRIBUTOR); + scheduling::printAddObjectError("PUS_PACKET_DISTRIB", objects::PUS_PACKET_DISTRIBUTOR); } result = tmTcDistributor->addComponent(objects::CFDP_DISTRIBUTOR); if (result != returnvalue::OK) { - initmission::printAddObjectError("CFDP_DISTRIBUTOR", objects::CFDP_DISTRIBUTOR); + scheduling::printAddObjectError("CFDP_DISTRIBUTOR", objects::CFDP_DISTRIBUTOR); } result = tmTcDistributor->addComponent(objects::TM_FUNNEL); if (result != returnvalue::OK) { - initmission::printAddObjectError("TM_FUNNEL", objects::TM_FUNNEL); + scheduling::printAddObjectError("TM_FUNNEL", objects::TM_FUNNEL); } #if OBSW_ADD_TCPIP_BRIDGE == 1 @@ -120,7 +120,7 @@ void initmission::initTasks() { "TMTC_POLLING", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); result = tmtcPollingTask->addComponent(objects::TMTC_POLLING_TASK); if (result != returnvalue::OK) { - initmission::printAddObjectError("UDP_POLLING", objects::TMTC_POLLING_TASK); + scheduling::printAddObjectError("UDP_POLLING", objects::TMTC_POLLING_TASK); } #endif @@ -129,7 +129,7 @@ void initmission::initTasks() { "CCSDS_HANDLER", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); result = ccsdsHandlerTask->addComponent(objects::CCSDS_HANDLER); if (result != returnvalue::OK) { - initmission::printAddObjectError("CCSDS Handler", objects::CCSDS_HANDLER); + scheduling::printAddObjectError("CCSDS Handler", objects::CCSDS_HANDLER); } // Runs in IRQ mode, frequency does not really matter @@ -137,7 +137,7 @@ void initmission::initTasks() { "PDEC_HANDLER", 75, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc); result = pdecHandlerTask->addComponent(objects::PDEC_HANDLER); if (result != returnvalue::OK) { - initmission::printAddObjectError("PDEC Handler", objects::PDEC_HANDLER); + scheduling::printAddObjectError("PDEC Handler", objects::PDEC_HANDLER); } #endif /* OBSW_ADD_CCSDS_IP_CORE == 1 */ @@ -146,7 +146,7 @@ void initmission::initTasks() { "CFDP Handler", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc); result = cfdpTask->addComponent(objects::CFDP_HANDLER); if (result != returnvalue::OK) { - initmission::printAddObjectError("CFDP Handler", objects::CFDP_HANDLER); + scheduling::printAddObjectError("CFDP Handler", objects::CFDP_HANDLER); } #endif @@ -155,14 +155,14 @@ void initmission::initTasks() { #if OBSW_ADD_GPS_CTRL == 1 result = acsCtrlTask->addComponent(objects::GPS_CONTROLLER); if (result != returnvalue::OK) { - initmission::printAddObjectError("GPS_CTRL", objects::GPS_CONTROLLER); + scheduling::printAddObjectError("GPS_CTRL", objects::GPS_CONTROLLER); } #endif /* OBSW_ADD_GPS_CTRL */ #if OBSW_ADD_ACS_CTRL == 1 acsCtrlTask->addComponent(objects::ACS_CONTROLLER); if (result != returnvalue::OK) { - initmission::printAddObjectError("ACS_CTRL", objects::ACS_CONTROLLER); + scheduling::printAddObjectError("ACS_CTRL", objects::ACS_CONTROLLER); } #endif @@ -172,24 +172,24 @@ void initmission::initTasks() { #if OBSW_ADD_ACS_BOARD == 1 result = acsSysTask->addComponent(objects::ACS_BOARD_ASS); if (result != returnvalue::OK) { - initmission::printAddObjectError("ACS_BOARD_ASS", objects::ACS_BOARD_ASS); + scheduling::printAddObjectError("ACS_BOARD_ASS", objects::ACS_BOARD_ASS); } #endif /* OBSW_ADD_ACS_HANDLERS */ #if OBSW_ADD_RW == 1 result = acsSysTask->addComponent(objects::RW_ASS); if (result != returnvalue::OK) { - initmission::printAddObjectError("RW_ASS", objects::RW_ASS); + scheduling::printAddObjectError("RW_ASS", objects::RW_ASS); } #endif #if OBSW_ADD_SUS_BOARD_ASS == 1 result = acsSysTask->addComponent(objects::SUS_BOARD_ASS); if (result != returnvalue::OK) { - initmission::printAddObjectError("SUS_BOARD_ASS", objects::SUS_BOARD_ASS); + scheduling::printAddObjectError("SUS_BOARD_ASS", objects::SUS_BOARD_ASS); } #endif result = acsSysTask->addComponent(objects::ACS_SUBSYSTEM); if (result != returnvalue::OK) { - initmission::printAddObjectError("ACS_SUBSYSTEM", objects::ACS_SUBSYSTEM); + scheduling::printAddObjectError("ACS_SUBSYSTEM", objects::ACS_SUBSYSTEM); } #if OBSW_ADD_RTD_DEVICES == 1 @@ -197,7 +197,7 @@ void initmission::initTasks() { "TCS_POLLING_TASK", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.5, missedDeadlineFunc); result = tcsPollingTask->addComponent(objects::SPI_RTD_COM_IF); if (result != returnvalue::OK) { - initmission::printAddObjectError("SPI_RTD_POLLING", objects::SPI_RTD_COM_IF); + scheduling::printAddObjectError("SPI_RTD_POLLING", objects::SPI_RTD_COM_IF); } PeriodicTaskIF* tcsTask = factory->createPeriodicTask( @@ -235,19 +235,19 @@ void initmission::initTasks() { #if OBSW_ADD_RTD_DEVICES == 1 result = tcsSystemTask->addComponent(objects::TCS_BOARD_ASS); if (result != returnvalue::OK) { - initmission::printAddObjectError("TCS_BOARD_ASS", objects::TCS_BOARD_ASS); + scheduling::printAddObjectError("TCS_BOARD_ASS", objects::TCS_BOARD_ASS); } #endif /* OBSW_ADD_RTD_DEVICES */ #if OBSW_ADD_TCS_CTRL == 1 result = tcsSystemTask->addComponent(objects::THERMAL_CONTROLLER); if (result != returnvalue::OK) { - initmission::printAddObjectError("THERMAL_CONTROLLER", objects::THERMAL_CONTROLLER); + scheduling::printAddObjectError("THERMAL_CONTROLLER", objects::THERMAL_CONTROLLER); } #endif #if OBSW_ADD_HEATERS == 1 result = tcsSystemTask->addComponent(objects::HEATER_HANDLER); if (result != returnvalue::OK) { - initmission::printAddObjectError("HEATER_HANDLER", objects::HEATER_HANDLER); + scheduling::printAddObjectError("HEATER_HANDLER", objects::HEATER_HANDLER); } #endif @@ -256,7 +256,7 @@ void initmission::initTasks() { "STR_HELPER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); result = strHelperTask->addComponent(objects::STR_HELPER); if (result != returnvalue::OK) { - initmission::printAddObjectError("STR_HELPER", objects::STR_HELPER); + scheduling::printAddObjectError("STR_HELPER", objects::STR_HELPER); } #endif /* OBSW_ADD_STAR_TRACKER == 1 */ @@ -265,7 +265,7 @@ void initmission::initTasks() { "PLOC_MPSOC_HELPER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); result = mpsocHelperTask->addComponent(objects::PLOC_MPSOC_HELPER); if (result != returnvalue::OK) { - initmission::printAddObjectError("PLOC_MPSOC_HELPER", objects::PLOC_MPSOC_HELPER); + scheduling::printAddObjectError("PLOC_MPSOC_HELPER", objects::PLOC_MPSOC_HELPER); } #endif /* OBSW_ADD_PLOC_MPSOC */ @@ -274,7 +274,7 @@ void initmission::initTasks() { "PLOC_SUPV_HELPER", 10, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc); result = supvHelperTask->addComponent(objects::PLOC_SUPERVISOR_HELPER); if (result != returnvalue::OK) { - initmission::printAddObjectError("PLOC_SUPV_HELPER", objects::PLOC_SUPERVISOR_HELPER); + scheduling::printAddObjectError("PLOC_SUPV_HELPER", objects::PLOC_SUPERVISOR_HELPER); } #endif /* OBSW_ADD_PLOC_SUPERVISOR */ @@ -300,7 +300,7 @@ void initmission::initTasks() { "PTME_TEST", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); result = ptmeTestTask->addComponent(objects::CCSDS_IP_CORE_BRIDGE); if (result != returnvalue::OK) { - initmission::printAddObjectError("PTME_TEST", objects::CCSDS_IP_CORE_BRIDGE); + scheduling::printAddObjectError("PTME_TEST", objects::CCSDS_IP_CORE_BRIDGE); } #endif std::vector testTasks; @@ -373,9 +373,8 @@ void initmission::initTasks() { sif::info << "Tasks started.." << std::endl; } -void initmission::createPstTasks(TaskFactory& factory, - TaskDeadlineMissedFunction missedDeadlineFunc, - std::vector& taskVec) { +void scheduling::createPstTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec) { ReturnValue_t result = returnvalue::OK; /* Polling Sequence Table Default */ #if OBSW_ADD_SPI_TEST_CODE == 0 @@ -384,9 +383,9 @@ void initmission::createPstTasks(TaskFactory& factory, result = pst::pstSpi(spiPst); if (result != returnvalue::OK) { if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { - sif::warning << "InitMission::initTasks: SPI PST is empty" << std::endl; + sif::warning << "scheduling::initTasks: SPI PST is empty" << std::endl; } else { - sif::error << "InitMission::initTasks: Creating SPI PST failed!" << std::endl; + sif::error << "scheduling::initTasks: Creating SPI PST failed!" << std::endl; } } else { taskVec.push_back(spiPst); @@ -399,9 +398,9 @@ void initmission::createPstTasks(TaskFactory& factory, result = pst::pstSpiRw(rwPstTask); if (result != returnvalue::OK) { if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { - sif::warning << "InitMission::initTasks: SPI PST is empty" << std::endl; + sif::warning << "scheduling::initTasks: SPI PST is empty" << std::endl; } else { - sif::error << "InitMission::initTasks: Creating SPI PST failed!" << std::endl; + sif::error << "scheduling::initTasks: Creating SPI PST failed!" << std::endl; } } else { taskVec.push_back(rwPstTask); @@ -413,9 +412,9 @@ void initmission::createPstTasks(TaskFactory& factory, result = pst::pstUart(uartPst); if (result != returnvalue::OK) { if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { - sif::warning << "InitMission::initTasks: UART PST is empty" << std::endl; + sif::warning << "scheduling::initTasks: UART PST is empty" << std::endl; } else { - sif::error << "InitMission::initTasks: Creating UART PST failed!" << std::endl; + sif::error << "scheduling::initTasks: Creating UART PST failed!" << std::endl; } } else { taskVec.push_back(uartPst); @@ -427,9 +426,9 @@ void initmission::createPstTasks(TaskFactory& factory, result = pst::pstI2c(i2cPst); if (result != returnvalue::OK) { if (result == FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { - sif::warning << "InitMission::initTasks: I2C PST is empty" << std::endl; + sif::warning << "scheduling::initTasks: I2C PST is empty" << std::endl; } else { - sif::error << "InitMission::initTasks: Creating I2C PST failed!" << std::endl; + sif::error << "scheduling::initTasks: Creating I2C PST failed!" << std::endl; } } else { taskVec.push_back(i2cPst); @@ -442,23 +441,22 @@ void initmission::createPstTasks(TaskFactory& factory, result = pst::pstGompaceCan(gomSpacePstTask); if (result != returnvalue::OK) { if (result != FixedTimeslotTaskIF::SLOT_LIST_EMPTY) { - sif::error << "InitMission::initTasks: GomSpace PST initialization failed!" << std::endl; + sif::error << "scheduling::initTasks: GomSpace PST initialization failed!" << std::endl; } } taskVec.push_back(gomSpacePstTask); #endif } -void initmission::createPusTasks(TaskFactory& factory, - TaskDeadlineMissedFunction missedDeadlineFunc, - std::vector& taskVec) { +void scheduling::createPusTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec) { ReturnValue_t result = returnvalue::OK; /* PUS Services */ PeriodicTaskIF* pusVerification = factory.createPeriodicTask( "PUS_VERIF", 40, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); result = pusVerification->addComponent(objects::PUS_SERVICE_1_VERIFICATION); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS_VERIF", objects::PUS_SERVICE_1_VERIFICATION); + scheduling::printAddObjectError("PUS_VERIF", objects::PUS_SERVICE_1_VERIFICATION); } taskVec.push_back(pusVerification); @@ -466,11 +464,11 @@ void initmission::createPusTasks(TaskFactory& factory, "PUS_EVENTS", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.200, missedDeadlineFunc); result = pusEvents->addComponent(objects::PUS_SERVICE_5_EVENT_REPORTING); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS_EVENTS", objects::PUS_SERVICE_5_EVENT_REPORTING); + scheduling::printAddObjectError("PUS_EVENTS", objects::PUS_SERVICE_5_EVENT_REPORTING); } result = pusEvents->addComponent(objects::EVENT_MANAGER); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS_MGMT", objects::EVENT_MANAGER); + scheduling::printAddObjectError("PUS_MGMT", objects::EVENT_MANAGER); } taskVec.push_back(pusEvents); @@ -478,11 +476,11 @@ void initmission::createPusTasks(TaskFactory& factory, "PUS_HIGH_PRIO", 50, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); result = pusHighPrio->addComponent(objects::PUS_SERVICE_2_DEVICE_ACCESS); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS_2", objects::PUS_SERVICE_2_DEVICE_ACCESS); + scheduling::printAddObjectError("PUS_2", objects::PUS_SERVICE_2_DEVICE_ACCESS); } result = pusHighPrio->addComponent(objects::PUS_SERVICE_9_TIME_MGMT); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS_9", objects::PUS_SERVICE_9_TIME_MGMT); + scheduling::printAddObjectError("PUS_9", objects::PUS_SERVICE_9_TIME_MGMT); } taskVec.push_back(pusHighPrio); @@ -492,32 +490,32 @@ void initmission::createPusTasks(TaskFactory& factory, result = pusMedPrio->addComponent(objects::PUS_SERVICE_3_HOUSEKEEPING); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS_3", objects::PUS_SERVICE_3_HOUSEKEEPING); + scheduling::printAddObjectError("PUS_3", objects::PUS_SERVICE_3_HOUSEKEEPING); } result = pusMedPrio->addComponent(objects::PUS_SERVICE_8_FUNCTION_MGMT); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS_8", objects::PUS_SERVICE_8_FUNCTION_MGMT); + scheduling::printAddObjectError("PUS_8", objects::PUS_SERVICE_8_FUNCTION_MGMT); } result = pusMedPrio->addComponent(objects::PUS_SERVICE_11_TC_SCHEDULER); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS_11", objects::PUS_SERVICE_11_TC_SCHEDULER); + scheduling::printAddObjectError("PUS_11", objects::PUS_SERVICE_11_TC_SCHEDULER); } result = pusMedPrio->addComponent(objects::PUS_SERVICE_20_PARAMETERS); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS_20", objects::PUS_SERVICE_20_PARAMETERS); + scheduling::printAddObjectError("PUS_20", objects::PUS_SERVICE_20_PARAMETERS); } result = pusMedPrio->addComponent(objects::PUS_SERVICE_200_MODE_MGMT); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS_200", objects::PUS_SERVICE_200_MODE_MGMT); + scheduling::printAddObjectError("PUS_200", objects::PUS_SERVICE_200_MODE_MGMT); } result = pusMedPrio->addComponent(objects::PUS_SERVICE_201_HEALTH); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS_201", objects::PUS_SERVICE_201_HEALTH); + scheduling::printAddObjectError("PUS_201", objects::PUS_SERVICE_201_HEALTH); } // Used for connection tests, therefore use higher priority result = pusMedPrio->addComponent(objects::PUS_SERVICE_17_TEST); if (result != returnvalue::OK) { - initmission::printAddObjectError("PUS_17", objects::PUS_SERVICE_17_TEST); + scheduling::printAddObjectError("PUS_17", objects::PUS_SERVICE_17_TEST); } taskVec.push_back(pusMedPrio); @@ -525,14 +523,14 @@ void initmission::createPusTasks(TaskFactory& factory, "PUS_LOW_PRIO", 30, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.6, missedDeadlineFunc); result = pusLowPrio->addComponent(objects::INTERNAL_ERROR_REPORTER); if (result != returnvalue::OK) { - initmission::printAddObjectError("ERROR_REPORTER", objects::INTERNAL_ERROR_REPORTER); + scheduling::printAddObjectError("ERROR_REPORTER", objects::INTERNAL_ERROR_REPORTER); } taskVec.push_back(pusLowPrio); } -void initmission::createTestTasks(TaskFactory& factory, - TaskDeadlineMissedFunction missedDeadlineFunc, - std::vector& taskVec) { +void scheduling::createTestTasks(TaskFactory& factory, + TaskDeadlineMissedFunction missedDeadlineFunc, + std::vector& taskVec) { #if OBSW_ADD_TEST_TASK == 1 && OBSW_ADD_TEST_CODE == 1 ReturnValue_t result = returnvalue::OK; static_cast(result); // supress warning in case it is not used @@ -542,25 +540,25 @@ void initmission::createTestTasks(TaskFactory& factory, result = testTask->addComponent(objects::TEST_TASK); if (result != returnvalue::OK) { - initmission::printAddObjectError("TEST_TASK", objects::TEST_TASK); + scheduling::printAddObjectError("TEST_TASK", objects::TEST_TASK); } #if OBSW_ADD_SPI_TEST_CODE == 1 result = testTask->addComponent(objects::SPI_TEST); if (result != returnvalue::OK) { - initmission::printAddObjectError("SPI_TEST", objects::SPI_TEST); + scheduling::printAddObjectError("SPI_TEST", objects::SPI_TEST); } #endif #if OBSW_ADD_I2C_TEST_CODE == 1 result = testTask->addComponent(objects::I2C_TEST); if (result != returnvalue::OK) { - initmission::printAddObjectError("I2C_TEST", objects::I2C_TEST); + scheduling::printAddObjectError("I2C_TEST", objects::I2C_TEST); } #endif #if OBSW_ADD_UART_TEST_CODE == 1 result = testTask->addComponent(objects::UART_TEST); if (result != returnvalue::OK) { - initmission::printAddObjectError("UART_TEST", objects::UART_TEST); + scheduling::printAddObjectError("UART_TEST", objects::UART_TEST); } #endif diff --git a/bsp_q7s/core/InitMission.h b/bsp_q7s/core/scheduling.h similarity index 92% rename from bsp_q7s/core/InitMission.h rename to bsp_q7s/core/scheduling.h index e0b1d8f2..d43575dc 100644 --- a/bsp_q7s/core/InitMission.h +++ b/bsp_q7s/core/scheduling.h @@ -8,7 +8,7 @@ class PeriodicTaskIF; class TaskFactory; -namespace initmission { +namespace scheduling { void initMission(); void initTasks(); @@ -18,6 +18,6 @@ void createPusTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadl std::vector& taskVec); void createTestTasks(TaskFactory& factory, TaskDeadlineMissedFunction missedDeadlineFunc, std::vector& taskVec); -}; // namespace initmission +}; // namespace scheduling #endif /* BSP_Q7S_INITMISSION_H_ */ diff --git a/bsp_q7s/em/emObjectFactory.cpp b/bsp_q7s/em/emObjectFactory.cpp index aba884f1..8d9edd6c 100644 --- a/bsp_q7s/em/emObjectFactory.cpp +++ b/bsp_q7s/em/emObjectFactory.cpp @@ -1,6 +1,7 @@ #include #include #include +#include #include "OBSWConfig.h" #include "bsp_q7s/core/CoreController.h" @@ -38,13 +39,21 @@ void ObjectFactory::produce(void* args) { #if OBSW_ADD_SYRLINKS == 1 dummyCfg.addSyrlinksDummies = false; #endif - dummy::createDummies(dummyCfg); +#if OBSW_ADD_GOMSPACE_PCDU == 1 + dummyCfg.addPowerDummies = false; +#endif + + PowerSwitchIF* pwrSwitcher = nullptr; +#if OBSW_ADD_GOMSPACE_PCDU == 0 + pwrSwitcher = new DummyPowerSwitcher(objects::PCDU_HANDLER, 18, 0); +#else + createPcduComponents(gpioComIF, &pwrSwitcher); +#endif + + dummy::createDummies(dummyCfg, *pwrSwitcher); new CoreController(objects::CORE_CONTROLLER); - PowerSwitchIF* pwrSwitcher = new DummyPowerSwitcher(objects::PCDU_HANDLER, 18, 0); - static_cast(pwrSwitcher); - // Regular FM code, does not work for EM if the hardware is not connected // createPcduComponents(gpioComIF, &pwrSwitcher); // createPlPcduComponents(gpioComIF, spiMainComIF, pwrSwitcher); @@ -95,8 +104,8 @@ void ObjectFactory::produce(void* args) { createTestComponents(gpioComIF); #endif /* OBSW_ADD_TEST_CODE == 1 */ #if OBSW_ADD_SCEX_DEVICE == 1 - createScexComponents(q7s::UART_SCEX_DEV, pwrSwitcher, *SdCardManager::instance(), true, - std::nullopt); + createScexComponents(q7s::UART_SCEX_DEV, pwrSwitcher, *SdCardManager::instance(), false, + pcdu::Switches::PDU1_CH5_SOLAR_CELL_EXP_5V); #endif createAcsController(true); } diff --git a/bsp_q7s/obsw.cpp b/bsp_q7s/obsw.cpp index 530c4904..d497eceb 100644 --- a/bsp_q7s/obsw.cpp +++ b/bsp_q7s/obsw.cpp @@ -5,7 +5,7 @@ #include "OBSWConfig.h" #include "commonConfig.h" -#include "core/InitMission.h" +#include "core/scheduling.h" #include "fsfw/tasks/TaskFactory.h" #include "fsfw/version.h" #include "q7sConfig.h" @@ -36,7 +36,7 @@ int obsw::obsw() { return OBSW_ALREADY_RUNNING; } #endif - initmission::initMission(); + scheduling::initMission(); for (;;) { /* Suspend main thread by sleeping it. */ diff --git a/cmake/scripts/cmake-build-cfg.py b/cmake/scripts/cmake-build-cfg.py index 4c5ee536..ea21fbdf 100755 --- a/cmake/scripts/cmake-build-cfg.py +++ b/cmake/scripts/cmake-build-cfg.py @@ -22,24 +22,38 @@ def main(): parser = argparse.ArgumentParser( description="Processing arguments for CMake build configuration." ) - parser.add_argument("-o", "--osal", type=str, choices=["freertos", "linux", "rtems", "host"], - help="FSFW OSAL. Valid arguments: host, linux, rtems, freertos") parser.add_argument( - "-b", "--buildtype", type=str, choices=["debug", "release", "size", "reldeb"], + "-o", + "--osal", + type=str, + choices=["freertos", "linux", "rtems", "host"], + help="FSFW OSAL. Valid arguments: host, linux, rtems, freertos", + ) + parser.add_argument( + "-b", + "--buildtype", + type=str, + choices=["debug", "release", "size", "reldeb"], help="CMake build type. Valid arguments: debug, release, size, reldeb (Release with Debug " - "Information)", default="debug" + "Information)", + default="debug", ) parser.add_argument("-l", "--builddir", type=str, help="Specify build directory.") parser.add_argument( - "-g", "--generator", type=str, help="CMake Generator", choices=['make', 'ninja'] + "-g", "--generator", type=str, help="CMake Generator", choices=["make", "ninja"] ) parser.add_argument( - "-d", "--defines", + "-d", + "--defines", help="Additional custom defines passed to CMake (supply without -D prefix!)", - nargs="*", type=str + nargs="*", + type=str, ) parser.add_argument( - "-t", "--target-bsp", type=str, help="Target BSP, combination of architecture and machine" + "-t", + "--target-bsp", + type=str, + help="Target BSP, combination of architecture and machine", ) args = parser.parse_args() @@ -59,13 +73,13 @@ def main(): if args.generator is None: generator_cmake_arg = "" else: - if args.generator == 'make': - if os.name == 'nt': + if args.generator == "make": + if os.name == "nt": generator_cmake_arg = '-G "MinGW Makefiles"' else: generator_cmake_arg = '-G "Unix Makefiles"' - elif args.generator == 'ninja': - generator_cmake_arg = '-G Ninja' + elif args.generator == "ninja": + generator_cmake_arg = "-G Ninja" else: generator_cmake_arg = args.generator @@ -79,7 +93,7 @@ def main(): cmake_build_type = "RelWithDebInfo" if args.target_bsp is not None: - cmake_target_cfg_cmd = f"-DTGT_BSP=\"{args.target_bsp}\"" + cmake_target_cfg_cmd = f'-DTGT_BSP="{args.target_bsp}"' else: cmake_target_cfg_cmd = "" @@ -92,10 +106,12 @@ def main(): build_folder = cmake_build_type if args.builddir is not None: build_folder = args.builddir - + build_path = source_location + os.path.sep + build_folder if os.path.isdir(build_path): - remove_old_dir = input(f"{build_folder} folder already exists. Remove old directory? [y/n]: ") + remove_old_dir = input( + f"{build_folder} folder already exists. Remove old directory? [y/n]: " + ) if str(remove_old_dir).lower() in ["yes", "y", 1]: remove_old_dir = True else: @@ -109,17 +125,19 @@ def main(): print(f"Navigating into build directory: {build_path}") os.chdir(build_folder) - cmake_command = f"cmake {generator_cmake_arg} -DFSFW_OSAL=\"{osal}\" " \ - f"-DCMAKE_BUILD_TYPE=\"{cmake_build_type}\" {cmake_target_cfg_cmd} " \ - f"{define_string} {source_location}" + cmake_command = ( + f'cmake {generator_cmake_arg} -DFSFW_OSAL="{osal}" ' + f'-DCMAKE_BUILD_TYPE="{cmake_build_type}" {cmake_target_cfg_cmd} ' + f"{define_string} {source_location}" + ) # Remove redundant spaces - cmake_command = ' '.join(cmake_command.split()) + cmake_command = " ".join(cmake_command.split()) print("Running CMake command: ") - print(f"\" {cmake_command} \"") + print(f'" {cmake_command} "') os.system(cmake_command) print("-- CMake configuration done. --") - - + + def rm_build_dir(path: str): # On windows the permissions of the build directory may have been set to read-only. If this # is the case the permissions are changed before trying to delete the directory. @@ -134,7 +152,9 @@ def determine_source_location() -> str: index += 1 os.chdir("..") if index >= 5: - print("Error: Could not find source directory (determined by looking for fsfw folder!)") + print( + "Error: Could not find source directory (determined by looking for fsfw folder!)" + ) sys.exit(1) return os.getcwd() diff --git a/common/config/commonConfig.h.in b/common/config/commonConfig.h.in index 83e1aaac..4fcc308f 100644 --- a/common/config/commonConfig.h.in +++ b/common/config/commonConfig.h.in @@ -19,12 +19,6 @@ debugging. */ // Disable this for mission code. It allows exchanging TMTC packets via the Ethernet port #define OBSW_ADD_TCPIP_BRIDGE 1 -// Use TCP instead of UDP for the TMTC bridge. This allows using the TMTC client locally -// because UDP packets are not allowed in the VPN -// This will cause the OBSW to initialize the TMTC bridge responsible for exchanging data with the -// CCSDS IP Cores. -#define OBSW_USE_TMTC_TCP_BRIDGE 1 - #define OBSW_ADD_CFDP_COMPONENTS 1 namespace common { diff --git a/common/config/devConf.h b/common/config/devConf.h index e5188324..931d1ad1 100644 --- a/common/config/devConf.h +++ b/common/config/devConf.h @@ -1,6 +1,8 @@ #ifndef COMMON_CONFIG_DEVCONF_H_ #define COMMON_CONFIG_DEVCONF_H_ +#include + #include #include "fsfw/timemanager/clockDefinitions.h" @@ -55,7 +57,7 @@ namespace uart { static constexpr size_t HYPERION_GPS_REPLY_MAX_BUFFER = 1024; static constexpr UartBaudRate SYRLINKS_BAUD = UartBaudRate::RATE_38400; -static constexpr UartBaudRate SCEX_BAUD = UartBaudRate::RATE_38400; +static constexpr UartBaudRate SCEX_BAUD = UartBaudRate::RATE_115200; static constexpr UartBaudRate GNSS_BAUD = UartBaudRate::RATE_9600; static constexpr UartBaudRate PLOC_MPSOC_BAUD = UartBaudRate::RATE_115200; static constexpr UartBaudRate PLOC_SUPV_BAUD = UartBaudRate::RATE_115200; diff --git a/linux/fsfwconfig/devices/addresses.h b/common/config/devices/addresses.h similarity index 100% rename from linux/fsfwconfig/devices/addresses.h rename to common/config/devices/addresses.h diff --git a/common/config/eive/objects.h b/common/config/eive/objects.h index f44c6354..a8911347 100644 --- a/common/config/eive/objects.h +++ b/common/config/eive/objects.h @@ -16,6 +16,10 @@ enum commonObjects : uint32_t { PDEC_HANDLER = 0x50000700, CCSDS_HANDLER = 0x50000800, + /* 0x49 ('I') for Communication Interfaces **/ + UART_COM_IF = 0x49030003, + SCEX_UART_READER = 0x49010006, + /* 0x43 ('C') for Controllers */ THERMAL_CONTROLLER = 0x43400001, ACS_CONTROLLER = 0x43000002, diff --git a/dummies/TemperatureSensorsDummy.cpp b/dummies/TemperatureSensorsDummy.cpp index 52190ee8..e7c75833 100644 --- a/dummies/TemperatureSensorsDummy.cpp +++ b/dummies/TemperatureSensorsDummy.cpp @@ -25,6 +25,10 @@ TemperatureSensorsDummy::TemperatureSensorsDummy() ObjectManager::instance()->insert(objects::RTD_15_IC18_IMTQ, this); ObjectManager::instance()->insert(objects::TMP1075_HANDLER_TCS_0, this); ObjectManager::instance()->insert(objects::TMP1075_HANDLER_TCS_1, this); + + ObjectManager::instance()->insert(objects::TMP1075_HANDLER_PLPCDU_0, this); + ObjectManager::instance()->insert(objects::TMP1075_HANDLER_PLPCDU_1, this); + ObjectManager::instance()->insert(objects::TMP1075_HANDLER_IF_BOARD, this); } ReturnValue_t TemperatureSensorsDummy::initialize() { diff --git a/dummies/helpers.cpp b/dummies/helpers.cpp index 495d6f6c..c489d3a0 100644 --- a/dummies/helpers.cpp +++ b/dummies/helpers.cpp @@ -19,10 +19,11 @@ #include #include #include +#include using namespace dummy; -void dummy::createDummies(DummyCfg cfg) { +void dummy::createDummies(DummyCfg cfg, PowerSwitchIF& pwrSwitch) { new ComIFDummy(objects::DUMMY_COM_IF); ComCookieDummy* comCookieDummy = new ComCookieDummy(); new BpxDummy(objects::BPX_BATT_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); @@ -67,5 +68,6 @@ void dummy::createDummies(DummyCfg cfg) { if (cfg.addTempSensorDummies) { new TemperatureSensorsDummy(); } + new CamSwitcher(objects::CAM_SWITCHER, pwrSwitch, power::NO_SWITCH); new PlPcduDummy(objects::PLPCDU_HANDLER, objects::DUMMY_COM_IF, comCookieDummy); } diff --git a/dummies/helpers.h b/dummies/helpers.h index f509f316..bbaab34d 100644 --- a/dummies/helpers.h +++ b/dummies/helpers.h @@ -1,5 +1,7 @@ #pragma once +#include + namespace dummy { struct DummyCfg { @@ -12,6 +14,6 @@ struct DummyCfg { bool addRtdComIFDummy = true; }; -void createDummies(DummyCfg cfg); +void createDummies(DummyCfg cfg, PowerSwitchIF& pwrSwitch); } // namespace dummy diff --git a/fsfw b/fsfw index 160ff799..8eb869e0 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 160ff799ace61e24708dcf1fdeaf5fafdf23a4ca +Subproject commit 8eb869e073d99e257c6cc62dbf26b4d99422e9b8 diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index 7dace6d3..e56b0ed6 100644 --- a/generators/bsp_q7s_events.csv +++ b/generators/bsp_q7s_events.csv @@ -123,10 +123,13 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 11901;0x2e7d;BOOTING_FIRMWARE_FAILED;LOW;Failed to boot firmware;linux/devices/startracker/StarTrackerHandler.h 11902;0x2e7e;BOOTING_BOOTLOADER_FAILED;LOW;Failed to boot star tracker into bootloader mode;linux/devices/startracker/StarTrackerHandler.h 12001;0x2ee1;SUPV_MEMORY_READ_RPT_CRC_FAILURE;LOW;PLOC supervisor crc failure in telemetry packet;linux/devices/ploc/PlocSupervisorHandler.h -12002;0x2ee2;SUPV_ACK_FAILURE;LOW;PLOC supervisor received acknowledgment failure report;linux/devices/ploc/PlocSupervisorHandler.h -12003;0x2ee3;SUPV_EXE_FAILURE;LOW;PLOC received execution failure report P1: ID of command for which the execution failed P2: Status code sent by the supervisor handler;linux/devices/ploc/PlocSupervisorHandler.h -12004;0x2ee4;SUPV_CRC_FAILURE_EVENT;LOW;PLOC supervisor reply has invalid crc;linux/devices/ploc/PlocSupervisorHandler.h -12005;0x2ee5;SUPV_MPSOC_SHUWDOWN_BUILD_FAILED;LOW;Failed to build the command to shutdown the MPSoC;linux/devices/ploc/PlocSupervisorHandler.h +12002;0x2ee2;SUPV_UNKNOWN_TM;LOW;Unhandled event. P1: APID, P2: Service ID;linux/devices/ploc/PlocSupervisorHandler.h +12003;0x2ee3;SUPV_UNINIMPLEMENTED_TM;LOW;;linux/devices/ploc/PlocSupervisorHandler.h +12004;0x2ee4;SUPV_ACK_FAILURE;LOW;PLOC supervisor received acknowledgment failure report;linux/devices/ploc/PlocSupervisorHandler.h +12005;0x2ee5;SUPV_EXE_FAILURE;LOW;PLOC received execution failure report P1: ID of command for which the execution failed P2: Status code sent by the supervisor handler;linux/devices/ploc/PlocSupervisorHandler.h +12006;0x2ee6;SUPV_CRC_FAILURE_EVENT;LOW;PLOC supervisor reply has invalid crc;linux/devices/ploc/PlocSupervisorHandler.h +12007;0x2ee7;SUPV_HELPER_EXECUTING;LOW;Supervisor helper currently executing a command;linux/devices/ploc/PlocSupervisorHandler.h +12008;0x2ee8;SUPV_MPSOC_SHUTDOWN_BUILD_FAILED;LOW;Failed to build the command to shutdown the MPSoC;linux/devices/ploc/PlocSupervisorHandler.h 12100;0x2f44;SANITIZATION_FAILED;LOW;;bsp_q7s/fs/SdCardManager.h 12101;0x2f45;MOUNTED_SD_CARD;INFO;;bsp_q7s/fs/SdCardManager.h 12300;0x300c;SEND_MRAM_DUMP_FAILED;LOW;Failed to send mram dump command to supervisor handler P1: Return value of commandAction function P2: Start address of MRAM to dump with this command;linux/devices/ploc/PlocMemoryDumper.h @@ -195,31 +198,33 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 13200;0x3390;P60_BOOT_COUNT;INFO;P60 boot count is broadcasted once at SW startup. P1: Boot count;mission/devices/P60DockHandler.h 13201;0x3391;BATT_MODE;INFO;Battery mode is broadcasted at startup. P1: Mode;mission/devices/P60DockHandler.h 13202;0x3392;BATT_MODE_CHANGED;MEDIUM;Battery mode has changed. P1: Old mode. P2: New mode;mission/devices/P60DockHandler.h -13600;0x3520;SUPV_UPDATE_FAILED;LOW;update failed;linux/devices/ploc/PlocSupvHelper.h -13601;0x3521;SUPV_UPDATE_SUCCESSFUL;LOW;update successful;linux/devices/ploc/PlocSupvHelper.h -13602;0x3522;SUPV_CONTINUE_UPDATE_FAILED;LOW;Continue update command failed;linux/devices/ploc/PlocSupvHelper.h -13603;0x3523;SUPV_CONTINUE_UPDATE_SUCCESSFUL;LOW;Continue update command successful;linux/devices/ploc/PlocSupvHelper.h -13604;0x3524;TERMINATED_UPDATE_PROCEDURE;LOW;Terminated update procedure by command;linux/devices/ploc/PlocSupvHelper.h -13605;0x3525;SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL;LOW;Requesting event buffer was successful;linux/devices/ploc/PlocSupvHelper.h -13606;0x3526;SUPV_EVENT_BUFFER_REQUEST_FAILED;LOW;Requesting event buffer failed;linux/devices/ploc/PlocSupvHelper.h -13607;0x3527;SUPV_EVENT_BUFFER_REQUEST_TERMINATED;LOW;Terminated event buffer request by command P1: Number of packets read before process was terminated;linux/devices/ploc/PlocSupvHelper.h -13608;0x3528;SUPV_MEM_CHECK_OK;INFO;;linux/devices/ploc/PlocSupvHelper.h -13609;0x3529;SUPV_MEM_CHECK_FAIL;INFO;;linux/devices/ploc/PlocSupvHelper.h -13616;0x3530;SUPV_SENDING_COMMAND_FAILED;LOW;;linux/devices/ploc/PlocSupvHelper.h -13617;0x3531;SUPV_HELPER_REQUESTING_REPLY_FAILED;LOW;Request receive message of communication interface failed P1: Return value returned by the communication interface requestReceiveMessage function P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvHelper.h -13618;0x3532;SUPV_HELPER_READING_REPLY_FAILED;LOW;Reading receive message of communication interface failed P1: Return value returned by the communication interface readingReceivedMessage function P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvHelper.h -13619;0x3533;SUPV_MISSING_ACK;LOW;Did not receive acknowledgement report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/devices/ploc/PlocSupvHelper.h -13620;0x3534;SUPV_MISSING_EXE;LOW;Supervisor did not receive execution report P1: Number of bytes missing P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvHelper.h -13621;0x3535;SUPV_ACK_FAILURE_REPORT;LOW;Supervisor received acknowledgment failure report P1: Internal state of supervisor helper;linux/devices/ploc/PlocSupvHelper.h -13622;0x3536;SUPV_EXE_FAILURE_REPORT;LOW;Execution report failure P1:;linux/devices/ploc/PlocSupvHelper.h -13623;0x3537;SUPV_ACK_INVALID_APID;LOW;Supervisor expected acknowledgment report but received space packet with other apid P1: Apid of received space packet P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvHelper.h -13624;0x3538;SUPV_EXE_INVALID_APID;LOW;Supervisor helper expected execution report but received space packet with other apid P1: Apid of received space packet P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvHelper.h -13625;0x3539;ACK_RECEPTION_FAILURE;LOW;Failed to receive acknowledgment report P1: Return value P2: Apid of command for which the reception of the acknowledgment report failed;linux/devices/ploc/PlocSupvHelper.h -13626;0x353a;EXE_RECEPTION_FAILURE;LOW;Failed to receive execution report P1: Return value P2: Apid of command for which the reception of the execution report failed;linux/devices/ploc/PlocSupvHelper.h -13627;0x353b;WRITE_MEMORY_FAILED;LOW;Update procedure failed when sending packet. P1: First byte percent, third and fourth byte Sequence Count, P2: Bytes written;linux/devices/ploc/PlocSupvHelper.h -13628;0x353c;SUPV_REPLY_SIZE_MISSMATCH;LOW;;linux/devices/ploc/PlocSupvHelper.h -13629;0x353d;SUPV_REPLY_CRC_MISSMATCH;LOW;;linux/devices/ploc/PlocSupvHelper.h -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/PlocSupvHelper.h +13600;0x3520;SUPV_UPDATE_FAILED;LOW;update failed;linux/devices/ploc/PlocSupvUartMan.h +13601;0x3521;SUPV_UPDATE_SUCCESSFUL;LOW;update successful;linux/devices/ploc/PlocSupvUartMan.h +13602;0x3522;SUPV_CONTINUE_UPDATE_FAILED;LOW;Continue update command failed;linux/devices/ploc/PlocSupvUartMan.h +13603;0x3523;SUPV_CONTINUE_UPDATE_SUCCESSFUL;LOW;Continue update command successful;linux/devices/ploc/PlocSupvUartMan.h +13604;0x3524;TERMINATED_UPDATE_PROCEDURE;LOW;Terminated update procedure by command;linux/devices/ploc/PlocSupvUartMan.h +13605;0x3525;SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL;LOW;Requesting event buffer was successful;linux/devices/ploc/PlocSupvUartMan.h +13606;0x3526;SUPV_EVENT_BUFFER_REQUEST_FAILED;LOW;Requesting event buffer failed;linux/devices/ploc/PlocSupvUartMan.h +13607;0x3527;SUPV_EVENT_BUFFER_REQUEST_TERMINATED;LOW;Terminated event buffer request by command P1: Number of packets read before process was terminated;linux/devices/ploc/PlocSupvUartMan.h +13608;0x3528;SUPV_MEM_CHECK_OK;INFO;;linux/devices/ploc/PlocSupvUartMan.h +13609;0x3529;SUPV_MEM_CHECK_FAIL;INFO;;linux/devices/ploc/PlocSupvUartMan.h +13616;0x3530;SUPV_SENDING_COMMAND_FAILED;LOW;;linux/devices/ploc/PlocSupvUartMan.h +13617;0x3531;SUPV_HELPER_REQUESTING_REPLY_FAILED;LOW;Request receive message of communication interface failed P1: Return value returned by the communication interface requestReceiveMessage function P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvUartMan.h +13618;0x3532;SUPV_HELPER_READING_REPLY_FAILED;LOW;Reading receive message of communication interface failed P1: Return value returned by the communication interface readingReceivedMessage function P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvUartMan.h +13619;0x3533;SUPV_MISSING_ACK;LOW;Did not receive acknowledgement report P1: Number of bytes missing P2: Internal state of MPSoC helper;linux/devices/ploc/PlocSupvUartMan.h +13620;0x3534;SUPV_MISSING_EXE;LOW;Supervisor did not receive execution report P1: Number of bytes missing P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvUartMan.h +13621;0x3535;SUPV_ACK_FAILURE_REPORT;LOW;Supervisor received acknowledgment failure report P1: Internal state of supervisor helper;linux/devices/ploc/PlocSupvUartMan.h +13622;0x3536;SUPV_EXE_FAILURE_REPORT;LOW;Execution report failure P1:;linux/devices/ploc/PlocSupvUartMan.h +13623;0x3537;SUPV_ACK_INVALID_APID;LOW;Supervisor expected acknowledgment report but received space packet with other apid P1: Apid of received space packet P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvUartMan.h +13624;0x3538;SUPV_EXE_INVALID_APID;LOW;Supervisor helper expected execution report but received space packet with other apid P1: Apid of received space packet P2: Internal state of supervisor helper;linux/devices/ploc/PlocSupvUartMan.h +13625;0x3539;ACK_RECEPTION_FAILURE;LOW;Failed to receive acknowledgment report P1: Return value P2: Apid of command for which the reception of the acknowledgment report failed;linux/devices/ploc/PlocSupvUartMan.h +13626;0x353a;EXE_RECEPTION_FAILURE;LOW;Failed to receive execution report P1: Return value P2: Apid of command for which the reception of the execution report failed;linux/devices/ploc/PlocSupvUartMan.h +13627;0x353b;WRITE_MEMORY_FAILED;LOW;Update procedure failed when sending packet. P1: First byte percent, third and fourth byte Sequence Count, P2: Bytes written;linux/devices/ploc/PlocSupvUartMan.h +13628;0x353c;SUPV_REPLY_SIZE_MISSMATCH;LOW;;linux/devices/ploc/PlocSupvUartMan.h +13629;0x353d;SUPV_REPLY_CRC_MISSMATCH;LOW;;linux/devices/ploc/PlocSupvUartMan.h +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;;linux/devices/ploc/PlocSupvUartMan.h +13632;0x3540;HDLC_CRC_ERROR;INFO;;linux/devices/ploc/PlocSupvUartMan.h 13700;0x3584;ALLOC_FAILURE;MEDIUM;;bsp_q7s/core/CoreController.h 13701;0x3585;REBOOT_SW;MEDIUM; Software reboot occurred. Can also be a systemd reboot. P1: Current Chip, P2: Current Copy;bsp_q7s/core/CoreController.h 13702;0x3586;REBOOT_MECHANISM_TRIGGERED;MEDIUM;The reboot mechanism was triggered. P1: First 16 bits: Last Chip, Last 16 bits: Last Copy, P2: Each byte is the respective reboot count for the slots;bsp_q7s/core/CoreController.h diff --git a/generators/bsp_q7s_returnvalues.csv b/generators/bsp_q7s_returnvalues.csv index 72c805b5..e64eed14 100644 --- a/generators/bsp_q7s_returnvalues.csv +++ b/generators/bsp_q7s_returnvalues.csv @@ -1,22 +1,13 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x0000;OK;System-wide code for ok.;0;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h 0x0001;Failed;Unspecified system-wide code for failed.;1;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h -0x63a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NVMParameterBase.h -0x58a0;SUSS_ErrorUnlockMutex;;160;SUS_HANDLER;mission/devices/SusHandler.h -0x58a1;SUSS_ErrorLockMutex;;161;SUS_HANDLER;mission/devices/SusHandler.h -0x66a0;SADPL_CommandNotSupported;;160;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h -0x66a1;SADPL_DeploymentAlreadyExecuting;;161;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h -0x66a2;SADPL_MainSwitchTimeoutFailure;;162;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h -0x66a3;SADPL_SwitchingDeplSa1Failed;;163;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h -0x66a4;SADPL_SwitchingDeplSa2Failed;;164;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h -0x51a0;IMTQ_InvalidCommandCode;;160;IMTQ_HANDLER;mission/devices/ImtqHandler.h -0x51a1;IMTQ_ParameterMissing;;161;IMTQ_HANDLER;mission/devices/ImtqHandler.h -0x51a2;IMTQ_ParameterInvalid;;162;IMTQ_HANDLER;mission/devices/ImtqHandler.h -0x51a3;IMTQ_CcUnavailable;;163;IMTQ_HANDLER;mission/devices/ImtqHandler.h -0x51a4;IMTQ_InternalProcessingError;;164;IMTQ_HANDLER;mission/devices/ImtqHandler.h -0x51a5;IMTQ_RejectedWithoutReason;;165;IMTQ_HANDLER;mission/devices/ImtqHandler.h -0x51a6;IMTQ_CmdErrUnknown;;166;IMTQ_HANDLER;mission/devices/ImtqHandler.h -0x51a7;IMTQ_UnexpectedSelfTestReply;The status reply to a self test command was received but no self test command has been sent. This should normally never happen.;167;IMTQ_HANDLER;mission/devices/ImtqHandler.h +0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h +0x5d00;GOMS_PacketTooLong;;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d01;GOMS_InvalidTableId;;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d02;GOMS_InvalidAddress;;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d03;GOMS_InvalidParamSize;;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d04;GOMS_InvalidPayloadSize;;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x5d05;GOMS_UnknownReplyId;;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x52b0;RWHA_SpiWriteFailure;;176;RW_HANDLER;mission/devices/RwHandler.h 0x52b1;RWHA_SpiReadFailure;Used by the spi send function to tell a failing read call;177;RW_HANDLER;mission/devices/RwHandler.h 0x52b2;RWHA_MissingStartSign;Can be used by the HDLC decoding mechanism to inform about a missing start sign 0x7E;178;RW_HANDLER;mission/devices/RwHandler.h @@ -29,12 +20,21 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x52a2;RWHA_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;RW_HANDLER;mission/devices/RwHandler.h 0x52a3;RWHA_ExecutionFailed;Command execution failed;163;RW_HANDLER;mission/devices/RwHandler.h 0x52a4;RWHA_CrcError;Reaction wheel reply has invalid crc;164;RW_HANDLER;mission/devices/RwHandler.h -0x5d00;GOMS_PacketTooLong;;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d01;GOMS_InvalidTableId;;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d02;GOMS_InvalidAddress;;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d03;GOMS_InvalidParamSize;;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d04;GOMS_InvalidPayloadSize;;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5d05;GOMS_UnknownReplyId;;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h +0x4fa1;HEATER_CommandNotSupported;;161;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x4fa2;HEATER_InitFailed;;162;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x4fa3;HEATER_InvalidSwitchNr;;163;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x4fa4;HEATER_MainSwitchSetTimeout;;164;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x4fa5;HEATER_CommandAlreadyWaiting;;165;HEATER_HANDLER;mission/devices/HeaterHandler.h +0x58a0;SUSS_ErrorUnlockMutex;;160;SUS_HANDLER;mission/devices/SusHandler.h +0x58a1;SUSS_ErrorLockMutex;;161;SUS_HANDLER;mission/devices/SusHandler.h +0x51a0;IMTQ_InvalidCommandCode;;160;IMTQ_HANDLER;mission/devices/ImtqHandler.h +0x51a1;IMTQ_ParameterMissing;;161;IMTQ_HANDLER;mission/devices/ImtqHandler.h +0x51a2;IMTQ_ParameterInvalid;;162;IMTQ_HANDLER;mission/devices/ImtqHandler.h +0x51a3;IMTQ_CcUnavailable;;163;IMTQ_HANDLER;mission/devices/ImtqHandler.h +0x51a4;IMTQ_InternalProcessingError;;164;IMTQ_HANDLER;mission/devices/ImtqHandler.h +0x51a5;IMTQ_RejectedWithoutReason;;165;IMTQ_HANDLER;mission/devices/ImtqHandler.h +0x51a6;IMTQ_CmdErrUnknown;;166;IMTQ_HANDLER;mission/devices/ImtqHandler.h +0x51a7;IMTQ_UnexpectedSelfTestReply;The status reply to a self test command was received but no self test command has been sent. This should normally never happen.;167;IMTQ_HANDLER;mission/devices/ImtqHandler.h 0x50a0;SYRLINKS_CrcFailure;;160;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h 0x50a1;SYRLINKS_UartFraminOrParityErrorAck;;161;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h 0x50a2;SYRLINKS_BadCharacterAck;;162;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h @@ -44,111 +44,130 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x50a6;SYRLINKS_BadCrcAck;;166;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h 0x50a7;SYRLINKS_ReplyWrongSize;;167;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h 0x50a8;SYRLINKS_MissingStartFrameCharacter;;168;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h -0x4fa1;HEATER_CommandNotSupported;;161;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4fa2;HEATER_InitFailed;;162;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4fa3;HEATER_InvalidSwitchNr;;163;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4fa4;HEATER_MainSwitchSetTimeout;;164;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4fa5;HEATER_CommandAlreadyWaiting;;165;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h -0x4500;HSPI_OpeningFileFailed;;0;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h -0x4501;HSPI_FullDuplexTransferFailed;;1;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h -0x4502;HSPI_HalfDuplexTransferFailed;;2;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h -0x4801;HGIO_UnknownGpioId;;1;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4802;HGIO_DriveGpioFailure;;2;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4803;HGIO_GpioTypeFailure;;3;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4804;HGIO_GpioInvalidInstance;;4;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4805;HGIO_GpioDuplicateDetected;;5;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4806;HGIO_GpioInitFailed;;6;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4807;HGIO_GpioGetValueFailed;;7;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4601;HURT_UartReadFailure;;1;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h -0x4602;HURT_UartReadSizeMissmatch;;2;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h -0x4603;HURT_UartRxBufferTooSmall;;3;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h -0x4400;UXOS_ExecutionFinished;Execution of the current command has finished;0;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4401;UXOS_CommandPending;Command is pending. This will also be returned if the user tries to load another command but a command is still pending;1;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4402;UXOS_BytesRead;Some bytes have been read from the executing process;2;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -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;;6;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x2801;SM_DataTooLarge;;1;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2802;SM_DataStorageFull;;2;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2803;SM_IllegalStorageId;;3;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2804;SM_DataDoesNotExist;;4;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2805;SM_IllegalAddress;;5;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2806;SM_PoolTooLarge;;6;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x0601;PP_DoItMyself;;1;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0602;PP_PointsToVariable;;2;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0603;PP_PointsToMemory;;3;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0604;PP_ActivityCompleted;;4;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0605;PP_PointsToVectorUint8;;5;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0606;PP_PointsToVectorUint16;;6;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0607;PP_PointsToVectorUint32;;7;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x0608;PP_PointsToVectorFloat;;8;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06a0;PP_DumpNotSupported;;160;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e0;PP_InvalidSize;;224;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e1;PP_InvalidAddress;;225;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e2;PP_InvalidContent;;226;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e3;PP_UnalignedAccess;;227;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x06e4;PP_WriteProtected;;228;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h -0x13e0;MH_UnknownCmd;;224;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h -0x13e1;MH_InvalidAddress;;225;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h -0x13e2;MH_InvalidSize;;226;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h -0x13e3;MH_StateMismatch;;227;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h -0x38a1;SGP4_InvalidEccentricity;;161;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a2;SGP4_InvalidMeanMotion;;162;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a3;SGP4_InvalidPerturbationElements;;163;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a4;SGP4_InvalidSemiLatusRectum;;164;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a5;SGP4_InvalidEpochElements;;165;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38a6;SGP4_SatelliteHasDecayed;;166;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38b1;SGP4_TleTooOld;;177;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x38b2;SGP4_TleNotInitialized;;178;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x1801;FF_Full;;1;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h -0x1802;FF_Empty;;2;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h -0x1601;FMM_MapFull;;1;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h -0x1602;FMM_KeyDoesNotExist;;2;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h -0x3901;MUX_NotEnoughResources;;1;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3902;MUX_InsufficientMemory;;2;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3903;MUX_NoPrivilege;;3;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3904;MUX_WrongAttributeSetting;;4;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3905;MUX_MutexAlreadyLocked;;5;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3906;MUX_MutexNotFound;;6;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3907;MUX_MutexMaxLocks;;7;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3908;MUX_CurrThreadAlreadyOwnsMutex;;8;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3909;MUX_CurrThreadDoesNotOwnMutex;;9;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x390a;MUX_MutexTimeout;;10;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x390b;MUX_MutexInvalidId;;11;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x390c;MUX_MutexDestroyedWhileWaiting;;12;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3a01;MQI_Empty;;1;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x3a02;MQI_Full;No space left for more messages;2;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x3a03;MQI_NoReplyPartner;Returned if a reply method was called without partner;3;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x3a04;MQI_DestinationInvalid;Returned if the target destination is invalid.;4;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x0f01;CM_UnknownCommand;;1;COMMAND_MESSAGE;fsfw/src/fsfw/ipc/CommandMessageIF.h +0x66a0;SADPL_CommandNotSupported;;160;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x66a1;SADPL_DeploymentAlreadyExecuting;;161;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x66a2;SADPL_MainSwitchTimeoutFailure;;162;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x66a3;SADPL_SwitchingDeplSa1Failed;;163;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x66a4;SADPL_SwitchingDeplSa2Failed;;164;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h +0x63a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NVMParameterBase.h +0x2c01;CCS_BcIsSetVrCommand;;1;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2c02;CCS_BcIsUnlockCommand;;2;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cb0;CCS_BcIllegalCommand;;176;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cb1;CCS_BoardReadingNotFinished;;177;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf0;CCS_NsPositiveW;;240;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf1;CCS_NsNegativeW;;241;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf2;CCS_NsLockout;;242;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf3;CCS_FarmInLockout;;243;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cf4;CCS_FarmInWait;;244;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce0;CCS_WrongSymbol;;224;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce1;CCS_DoubleStart;;225;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce2;CCS_StartSymbolMissed;;226;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce3;CCS_EndWithoutStart;;227;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce4;CCS_TooLarge;;228;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce5;CCS_TooShort;;229;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce6;CCS_WrongTfVersion;;230;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce7;CCS_WrongSpacecraftId;;231;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce8;CCS_NoValidFrameType;;232;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ce9;CCS_CrcFailed;;233;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cea;CCS_VcNotFound;;234;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ceb;CCS_ForwardingFailed;;235;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cec;CCS_ContentTooLarge;;236;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2ced;CCS_ResidualData;;237;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cee;CCS_DataCorrupted;;238;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cef;CCS_IllegalSegmentationFlag;;239;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cd0;CCS_IllegalFlagCombination;;208;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cd1;CCS_ShorterThanHeader;;209;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cd2;CCS_TooShortBlockedPacket;;210;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x2cd3;CCS_TooShortMapExtraction;;211;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h +0x3b00;SPH_ConnBroken;;0;SEMAPHORE_IF;fsfw/src/fsfw/osal/common/TcpTmTcServer.h +0x2a01;IEC_NoConfigurationTable;;1;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a02;IEC_NoCpuTable;;2;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a03;IEC_InvalidWorkspaceAddress;;3;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a04;IEC_TooLittleWorkspace;;4;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a05;IEC_WorkspaceAllocation;;5;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a06;IEC_InterruptStackTooSmall;;6;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a07;IEC_ThreadExitted;;7;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a08;IEC_InconsistentMpInformation;;8;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a09;IEC_InvalidNode;;9;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0a;IEC_NoMpci;;10;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0b;IEC_BadPacket;;11;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0c;IEC_OutOfPackets;;12;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0d;IEC_OutOfGlobalObjects;;13;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0e;IEC_OutOfProxies;;14;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a0f;IEC_InvalidGlobalId;;15;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a10;IEC_BadStackHook;;16;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a11;IEC_BadAttributes;;17;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a12;IEC_ImplementationKeyCreateInconsistency;;18;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a13;IEC_ImplementationBlockingOperationCancel;;19;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a14;IEC_MutexObtainFromBadState;;20;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h +0x2a15;IEC_UnlimitedAndMaximumIs0;;21;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x0e01;HM_InvalidMode;;1;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h 0x0e02;HM_TransNotAllowed;;2;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h 0x0e03;HM_InTransition;;3;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h 0x0e04;HM_InvalidSubmode;;4;HAS_MODES_IF;fsfw/src/fsfw/modes/HasModesIF.h -0x0c02;MS_InvalidEntry;;2;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h -0x0c03;MS_TooManyElements;;3;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h -0x0c04;MS_CantStoreEmpty;;4;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h -0x0b01;SB_ChildNotFound;;1;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0b02;SB_ChildInfoUpdated;;2;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0b03;SB_ChildDoesntHaveModes;;3;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0b04;SB_CouldNotInsertChild;;4;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0b05;SB_TableContainsInvalidObjectId;;5;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h -0x0d01;SS_SequenceAlreadyExists;;1;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d02;SS_TableAlreadyExists;;2;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d03;SS_TableDoesNotExist;;3;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d04;SS_TableOrSequenceLengthInvalid;;4;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d05;SS_SequenceDoesNotExist;;5;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d06;SS_TableContainsInvalidObjectId;;6;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d07;SS_FallbackSequenceDoesNotExist;;7;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d08;SS_NoTargetTable;;8;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d09;SS_SequenceOrTableTooLong;;9;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d0b;SS_IsFallbackSequence;;11;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d0c;SS_AccessDenied;;12;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0d0e;SS_TableInUse;;14;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0da1;SS_TargetTableNotReached;;161;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x0da2;SS_TableCheckFailed;;162;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h -0x2501;EV_ListenerNotFound;;1;EVENT_MANAGER_IF;fsfw/src/fsfw/events/EventManagerIF.h +0x2e01;HPA_InvalidIdentifierId;;1;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2e02;HPA_InvalidDomainId;;2;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2e03;HPA_InvalidValue;;3;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2e05;HPA_ReadOnly;;5;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h +0x2d01;PAW_UnknownDatatype;;1;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d02;PAW_DatatypeMissmatch;;2;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d03;PAW_Readonly;;3;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d04;PAW_TooBig;;4;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d05;PAW_SourceNotSet;;5;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d06;PAW_OutOfBounds;;6;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d07;PAW_NotSet;;7;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x2d08;PAW_ColumnOrRowsZero;;8;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h +0x3201;CF_ObjectHasNoFunctions;;1;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h +0x3202;CF_AlreadyCommanding;;2;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h +0x3301;HF_IsBusy;;1;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x3302;HF_InvalidParameters;;2;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x3303;HF_ExecutionFinished;;3;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x3304;HF_InvalidActionId;;4;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h +0x0201;OM_InsertionFailed;;1;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x0202;OM_NotFound;;2;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x0203;OM_ChildInitFailed;;3;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x0204;OM_InternalErrReporterUninit;;4;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h +0x2600;FDI_YourFault;;0;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h +0x2601;FDI_MyFault;;1;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h +0x2602;FDI_ConfirmLater;;2;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h +0x2201;TMF_Busy;;1;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2202;TMF_LastPacketFound;;2;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2203;TMF_StopFetch;;3;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2204;TMF_Timeout;;4;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2205;TMF_TmChannelFull;;5;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2206;TMF_NotStored;;6;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2207;TMF_AllDeleted;;7;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2208;TMF_InvalidData;;8;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2209;TMF_NotReady;;9;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h +0x2101;TMB_Busy;;1;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2102;TMB_Full;;2;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2103;TMB_Empty;;3;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2104;TMB_NullRequested;;4;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2105;TMB_TooLarge;;5;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2106;TMB_NotReady;;6;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2107;TMB_DumpError;;7;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2108;TMB_CrcError;;8;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x2109;TMB_Timeout;;9;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210a;TMB_IdlePacketFound;;10;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210b;TMB_TelecommandFound;;11;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210c;TMB_NoPusATm;;12;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210d;TMB_TooSmall;;13;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210e;TMB_BlockNotFound;;14;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x210f;TMB_InvalidRequest;;15;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h +0x1c01;TCD_PacketLost;;1;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h +0x1c02;TCD_DestinationNotFound;;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h +0x1c03;TCD_ServiceIdAlreadyExists;;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h +0x1b00;TCC_NoDestinationFound;;0;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b01;TCC_InvalidCcsdsVersion;;1;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b02;TCC_InvalidApid;;2;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b03;TCC_InvalidPacketType;;3;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b04;TCC_InvalidSecHeaderField;;4;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b05;TCC_IncorrectPrimaryHeader;;5;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b07;TCC_IncompletePacket;;7;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b08;TCC_InvalidPusVersion;;8;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b09;TCC_IncorrectChecksum;;9;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b0a;TCC_IllegalPacketSubtype;;10;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b0b;TCC_IncorrectSecondaryHeader;;11;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h 0x04e1;RMP_CommandNoDescriptorsAvailable;;225;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x04e2;RMP_CommandBufferFull;;226;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x04e3;RMP_CommandChannelOutOfRange;;227;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h @@ -189,9 +208,95 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x040a;RMP_ReplyCommandNotImplementedOrNotAuthorised;;10;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x040b;RMP_ReplyRmwDataLengthError;;11;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x040c;RMP_ReplyInvalidTargetLogicalAddress;;12;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h -0x1401;SE_BufferTooShort;;1;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h -0x1402;SE_StreamTooShort;;2;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h -0x1403;SE_TooManyElements;;3;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x2801;SM_DataTooLarge;;1;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2802;SM_DataStorageFull;;2;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2803;SM_IllegalStorageId;;3;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2804;SM_DataDoesNotExist;;4;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2805;SM_IllegalAddress;;5;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x2806;SM_PoolTooLarge;;6;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h +0x38a1;SGP4_InvalidEccentricity;;161;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a2;SGP4_InvalidMeanMotion;;162;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a3;SGP4_InvalidPerturbationElements;;163;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a4;SGP4_InvalidSemiLatusRectum;;164;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a5;SGP4_InvalidEpochElements;;165;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38a6;SGP4_SatelliteHasDecayed;;166;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38b1;SGP4_TleTooOld;;177;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x38b2;SGP4_TleNotInitialized;;178;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h +0x2401;MT_NoPacketFound;;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h +0x2402;MT_PossiblePacketLoss;;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h +0x2403;MT_NoMatch;;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x2404;MT_Full;;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x2405;MT_NewNodeCreated;;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h +0x3f01;DLEE_StreamTooShort;;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h +0x3f02;DLEE_DecodingError;;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h +0x2f01;ASC_TooLongForTargetType;;1;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h +0x2f02;ASC_InvalidCharacters;;2;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h +0x2f03;ASC_BufferTooSmall;;3;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h +0x0f01;CM_UnknownCommand;;1;COMMAND_MESSAGE;fsfw/src/fsfw/ipc/CommandMessageIF.h +0x3a01;MQI_Empty;;1;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3a02;MQI_Full;No space left for more messages;2;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3a03;MQI_NoReplyPartner;Returned if a reply method was called without partner;3;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3a04;MQI_DestinationInvalid;Returned if the target destination is invalid.;4;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h +0x3901;MUX_NotEnoughResources;;1;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3902;MUX_InsufficientMemory;;2;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3903;MUX_NoPrivilege;;3;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3904;MUX_WrongAttributeSetting;;4;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3905;MUX_MutexAlreadyLocked;;5;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3906;MUX_MutexNotFound;;6;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3907;MUX_MutexMaxLocks;;7;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3908;MUX_CurrThreadAlreadyOwnsMutex;;8;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3909;MUX_CurrThreadDoesNotOwnMutex;;9;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x390a;MUX_MutexTimeout;;10;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x390b;MUX_MutexInvalidId;;11;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x390c;MUX_MutexDestroyedWhileWaiting;;12;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h +0x3b01;SPH_SemaphoreTimeout;;1;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x3b02;SPH_SemaphoreNotOwned;;2;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x3b03;SPH_SemaphoreInvalid;;3;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x1e00;PUS_InvalidPusVersion;;0;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h +0x1e01;PUS_InvalidCrc16;;1;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h +0x3601;CFDP_InvalidTlvType;;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3602;CFDP_InvalidDirectiveField;;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3603;CFDP_InvalidPduDatafieldLen;;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3604;CFDP_InvalidAckDirectiveFields;;4;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3605;CFDP_MetadataCantParseOptions;;5;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3606;CFDP_NakCantParseOptions;;6;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3607;CFDP_FinishedCantParseFsResponses;;7;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3608;CFDP_FilestoreRequiresSecondFile;;8;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x3609;CFDP_FilestoreResponseCantParseFsMessage;;9;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x360a;CFDP_InvalidPduFormat;;10;CFDP;fsfw/src/fsfw/cfdp/definitions.h +0x2901;TC_InvalidTargetState;;1;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h +0x29f1;TC_AboveOperationalLimit;;241;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h +0x29f2;TC_BelowOperationalLimit;;242;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h +0x0c02;MS_InvalidEntry;;2;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h +0x0c03;MS_TooManyElements;;3;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h +0x0c04;MS_CantStoreEmpty;;4;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h +0x0d01;SS_SequenceAlreadyExists;;1;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d02;SS_TableAlreadyExists;;2;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d03;SS_TableDoesNotExist;;3;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d04;SS_TableOrSequenceLengthInvalid;;4;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d05;SS_SequenceDoesNotExist;;5;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d06;SS_TableContainsInvalidObjectId;;6;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d07;SS_FallbackSequenceDoesNotExist;;7;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d08;SS_NoTargetTable;;8;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d09;SS_SequenceOrTableTooLong;;9;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d0b;SS_IsFallbackSequence;;11;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d0c;SS_AccessDenied;;12;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0d0e;SS_TableInUse;;14;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0da1;SS_TargetTableNotReached;;161;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0da2;SS_TableCheckFailed;;162;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h +0x0b01;SB_ChildNotFound;;1;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b02;SB_ChildInfoUpdated;;2;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b03;SB_ChildDoesntHaveModes;;3;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b04;SB_CouldNotInsertChild;;4;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x0b05;SB_TableContainsInvalidObjectId;;5;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h +0x3e00;HKM_QueueOrDestinationInvalid;;0;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e01;HKM_WrongHkPacketType;;1;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e02;HKM_ReportingStatusUnchanged;;2;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e03;HKM_PeriodicHelperInvalid;;3;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e04;HKM_PoolobjectNotFound;;4;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3e05;HKM_DatasetNotFound;;5;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h +0x3c00;LPIF_PoolEntryNotFound;;0;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h +0x3c01;LPIF_PoolEntryTypeConflict;;1;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h 0x3da0;PVA_InvalidReadWriteMode;;160;POOL_VARIABLE_IF;fsfw/src/fsfw/datapool/PoolVariableIF.h 0x3da1;PVA_InvalidPoolEntry;;161;POOL_VARIABLE_IF;fsfw/src/fsfw/datapool/PoolVariableIF.h 0x0801;DPS_InvalidParameterDefinition;;1;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h @@ -200,20 +305,35 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x0804;DPS_DataSetUninitialised;;4;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h 0x0805;DPS_DataSetFull;;5;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h 0x0806;DPS_PoolVarNull;;6;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h -0x1c01;TCD_PacketLost;;1;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h -0x1c02;TCD_DestinationNotFound;;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h -0x1c03;TCD_ServiceIdAlreadyExists;;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h -0x1b00;TCC_NoDestinationFound;;0;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b01;TCC_InvalidCcsdsVersion;;1;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b02;TCC_InvalidApid;;2;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b03;TCC_InvalidPacketType;;3;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b04;TCC_InvalidSecHeaderField;;4;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b05;TCC_IncorrectPrimaryHeader;;5;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b07;TCC_IncompletePacket;;7;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b08;TCC_InvalidPusVersion;;8;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b09;TCC_IncorrectChecksum;;9;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b0a;TCC_IllegalPacketSubtype;;10;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b0b;TCC_IncorrectSecondaryHeader;;11;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h +0x1000;TIM_UnsupportedTimeFormat;;0;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1001;TIM_NotEnoughInformationForTargetFormat;;1;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1002;TIM_LengthMismatch;;2;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1003;TIM_InvalidTimeFormat;;3;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1004;TIM_InvalidDayOfYear;;4;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x1005;TIM_TimeDoesNotFitFormat;;5;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h +0x3701;TSI_BadTimestamp;;1;TIME_STAMPER_IF;fsfw/src/fsfw/timemanager/TimeStampIF.h +0x1d01;ATC_ActivityStarted;;1;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d02;ATC_InvalidSubservice;;2;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d03;ATC_IllegalApplicationData;;3;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d04;ATC_SendTmFailed;;4;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x1d05;ATC_Timeout;;5;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h +0x4c00;SPPA_NoPacketFound;;0;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h +0x4c01;SPPA_SplitPacket;;1;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h +0x2001;CSB_ExecutionComplete;;1;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2002;CSB_NoStepMessage;;2;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2003;CSB_ObjectBusy;;3;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2004;CSB_Busy;;4;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2005;CSB_InvalidTc;;5;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2006;CSB_InvalidObject;;6;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x2007;CSB_InvalidReply;;7;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h +0x1801;FF_Full;;1;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h +0x1802;FF_Empty;;2;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h +0x1601;FMM_MapFull;;1;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h +0x1602;FMM_KeyDoesNotExist;;2;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h +0x2501;EV_ListenerNotFound;;1;EVENT_MANAGER_IF;fsfw/src/fsfw/events/EventManagerIF.h +0x1701;HHI_ObjectNotHealthy;;1;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h +0x1702;HHI_InvalidHealthState;;2;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h +0x1703;HHI_IsExternallyControlled;;3;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h 0x3001;POS_InPowerTransition;;1;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h 0x3002;POS_SwitchStateMismatch;;2;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h 0x0501;PS_SwitchOn;;1;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h @@ -221,76 +341,23 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x0502;PS_SwitchTimeout;;2;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h 0x0503;PS_FuseOn;;3;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h 0x0504;PS_FuseOff;;4;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h -0x3b00;SPH_ConnBroken;;0;SEMAPHORE_IF;fsfw/src/fsfw/osal/common/TcpTmTcServer.h -0x2a01;IEC_NoConfigurationTable;;1;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a02;IEC_NoCpuTable;;2;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a03;IEC_InvalidWorkspaceAddress;;3;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a04;IEC_TooLittleWorkspace;;4;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a05;IEC_WorkspaceAllocation;;5;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a06;IEC_InterruptStackTooSmall;;6;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a07;IEC_ThreadExitted;;7;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a08;IEC_InconsistentMpInformation;;8;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a09;IEC_InvalidNode;;9;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0a;IEC_NoMpci;;10;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0b;IEC_BadPacket;;11;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0c;IEC_OutOfPackets;;12;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0d;IEC_OutOfGlobalObjects;;13;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0e;IEC_OutOfProxies;;14;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a0f;IEC_InvalidGlobalId;;15;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a10;IEC_BadStackHook;;16;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a11;IEC_BadAttributes;;17;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a12;IEC_ImplementationKeyCreateInconsistency;;18;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a13;IEC_ImplementationBlockingOperationCancel;;19;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a14;IEC_MutexObtainFromBadState;;20;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2a15;IEC_UnlimitedAndMaximumIs0;;21;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2600;FDI_YourFault;;0;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h -0x2601;FDI_MyFault;;1;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h -0x2602;FDI_ConfirmLater;;2;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h -0x1e00;PUS_InvalidPusVersion;;0;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h -0x1e01;PUS_InvalidCrc16;;1;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h -0x0201;OM_InsertionFailed;;1;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h -0x0202;OM_NotFound;;2;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h -0x0203;OM_ChildInitFailed;;3;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h -0x0204;OM_InternalErrReporterUninit;;4;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h -0x2201;TMF_Busy;;1;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2202;TMF_LastPacketFound;;2;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2203;TMF_StopFetch;;3;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2204;TMF_Timeout;;4;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2205;TMF_TmChannelFull;;5;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2206;TMF_NotStored;;6;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2207;TMF_AllDeleted;;7;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2208;TMF_InvalidData;;8;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2209;TMF_NotReady;;9;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2101;TMB_Busy;;1;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2102;TMB_Full;;2;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2103;TMB_Empty;;3;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2104;TMB_NullRequested;;4;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2105;TMB_TooLarge;;5;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2106;TMB_NotReady;;6;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2107;TMB_DumpError;;7;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2108;TMB_CrcError;;8;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2109;TMB_Timeout;;9;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210a;TMB_IdlePacketFound;;10;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210b;TMB_TelecommandFound;;11;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210c;TMB_NoPusATm;;12;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210d;TMB_TooSmall;;13;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210e;TMB_BlockNotFound;;14;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x210f;TMB_InvalidRequest;;15;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2d01;PAW_UnknownDatatype;;1;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d02;PAW_DatatypeMissmatch;;2;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d03;PAW_Readonly;;3;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d04;PAW_TooBig;;4;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d05;PAW_SourceNotSet;;5;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d06;PAW_OutOfBounds;;6;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d07;PAW_NotSet;;7;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2d08;PAW_ColumnOrRowsZero;;8;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2e01;HPA_InvalidIdentifierId;;1;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x2e02;HPA_InvalidDomainId;;2;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x2e03;HPA_InvalidValue;;3;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x2e05;HPA_ReadOnly;;5;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x3b01;SPH_SemaphoreTimeout;;1;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h -0x3b02;SPH_SemaphoreNotOwned;;2;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h -0x3b03;SPH_SemaphoreInvalid;;3;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h +0x4300;FILS_GenericFileError;;0;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4301;FILS_GenericDirError;;1;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4302;FILS_FilesystemInactive;;2;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4303;FILS_GenericRenameError;;3;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4304;FILS_IsBusy;;4;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4305;FILS_InvalidParameters;;5;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430a;FILS_FileDoesNotExist;;10;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430b;FILS_FileAlreadyExists;;11;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430c;FILS_NotAFile;;12;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430d;FILS_FileLocked;;13;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x430e;FILS_PermissionDenied;;14;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4315;FILS_DirectoryDoesNotExist;;21;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4316;FILS_DirectoryAlreadyExists;;22;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4317;FILS_NotADirectory;;23;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x4318;FILS_DirectoryNotEmpty;;24;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x431e;FILS_SequencePacketMissingWrite;;30;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h +0x431f;FILS_SequencePacketMissingRead;;31;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x1a01;TRC_NotEnoughSensors;;1;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h 0x1a02;TRC_LowestValueOol;;2;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h 0x1a03;TRC_HighestValueOol;;3;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h @@ -309,72 +376,34 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x31e2;LIM_WrongPid;;226;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h 0x31e3;LIM_WrongLimitId;;227;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h 0x31ee;LIM_MonitorNotFound;;238;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x3601;CFDP_InvalidTlvType;;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3602;CFDP_InvalidDirectiveField;;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3603;CFDP_InvalidPduDatafieldLen;;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3604;CFDP_InvalidAckDirectiveFields;;4;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3605;CFDP_MetadataCantParseOptions;;5;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3606;CFDP_NakCantParseOptions;;6;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3607;CFDP_FinishedCantParseFsResponses;;7;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3608;CFDP_FilestoreRequiresSecondFile;;8;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3609;CFDP_FilestoreResponseCantParseFsMessage;;9;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x360a;CFDP_InvalidPduFormat;;10;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x4300;FILS_GenericFileError;;0;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4301;FILS_GenericDirError;;1;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4302;FILS_FilesystemInactive;;2;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4303;FILS_GenericRenameError;;3;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4304;FILS_IsBusy;;4;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4305;FILS_InvalidParameters;;5;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430a;FILS_FileDoesNotExist;;10;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430b;FILS_FileAlreadyExists;;11;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430c;FILS_NotAFile;;12;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430d;FILS_FileLocked;;13;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x430e;FILS_PermissionDenied;;14;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4315;FILS_DirectoryDoesNotExist;;21;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4316;FILS_DirectoryAlreadyExists;;22;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4317;FILS_NotADirectory;;23;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x4318;FILS_DirectoryNotEmpty;;24;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x431e;FILS_SequencePacketMissingWrite;;30;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x431f;FILS_SequencePacketMissingRead;;31;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h -0x2c01;CCS_BcIsSetVrCommand;;1;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2c02;CCS_BcIsUnlockCommand;;2;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cb0;CCS_BcIllegalCommand;;176;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cb1;CCS_BoardReadingNotFinished;;177;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf0;CCS_NsPositiveW;;240;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf1;CCS_NsNegativeW;;241;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf2;CCS_NsLockout;;242;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf3;CCS_FarmInLockout;;243;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cf4;CCS_FarmInWait;;244;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce0;CCS_WrongSymbol;;224;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce1;CCS_DoubleStart;;225;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce2;CCS_StartSymbolMissed;;226;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce3;CCS_EndWithoutStart;;227;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce4;CCS_TooLarge;;228;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce5;CCS_TooShort;;229;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce6;CCS_WrongTfVersion;;230;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce7;CCS_WrongSpacecraftId;;231;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce8;CCS_NoValidFrameType;;232;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ce9;CCS_CrcFailed;;233;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cea;CCS_VcNotFound;;234;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ceb;CCS_ForwardingFailed;;235;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cec;CCS_ContentTooLarge;;236;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2ced;CCS_ResidualData;;237;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cee;CCS_DataCorrupted;;238;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cef;CCS_IllegalSegmentationFlag;;239;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cd0;CCS_IllegalFlagCombination;;208;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cd1;CCS_ShorterThanHeader;;209;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cd2;CCS_TooShortBlockedPacket;;210;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2cd3;CCS_TooShortMapExtraction;;211;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4201;PUS11_InvalidTypeTimeWindow;;1;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4202;PUS11_InvalidTimeWindow;;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4203;PUS11_TimeshiftingNotPossible;;3;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4204;PUS11_InvalidRelativeTime;;4;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h -0x3401;DC_NoReplyReceived;;1;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3402;DC_ProtocolError;;2;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3403;DC_Nullpointer;;3;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3404;DC_InvalidCookieType;;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3405;DC_NotActive;;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3406;DC_TooMuchData;;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x0601;PP_DoItMyself;;1;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0602;PP_PointsToVariable;;2;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0603;PP_PointsToMemory;;3;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0604;PP_ActivityCompleted;;4;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0605;PP_PointsToVectorUint8;;5;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0606;PP_PointsToVectorUint16;;6;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0607;PP_PointsToVectorUint32;;7;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x0608;PP_PointsToVectorFloat;;8;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06a0;PP_DumpNotSupported;;160;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e0;PP_InvalidSize;;224;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e1;PP_InvalidAddress;;225;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e2;PP_InvalidContent;;226;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e3;PP_UnalignedAccess;;227;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x06e4;PP_WriteProtected;;228;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h +0x13e0;MH_UnknownCmd;;224;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x13e1;MH_InvalidAddress;;225;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x13e2;MH_InvalidSize;;226;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x13e3;MH_StateMismatch;;227;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h +0x1201;AB_NeedSecondStep;;1;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1202;AB_NeedToReconfigure;;2;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1203;AB_ModeFallback;;3;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1204;AB_ChildNotCommandable;;4;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x1205;AB_NeedToChangeHealth;;5;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x12a1;AB_NotEnoughChildrenInCorrectState;;161;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h 0x03a0;DHB_InvalidChannel;;160;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h 0x03b0;DHB_AperiodicReply;;176;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h 0x03b1;DHB_IgnoreReplyData;;177;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h @@ -384,12 +413,12 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x03d0;DHB_NoSwitch;;208;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h 0x03e0;DHB_ChildTimeout;;224;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h 0x03e1;DHB_SwitchFailed;;225;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h -0x1201;AB_NeedSecondStep;;1;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x1202;AB_NeedToReconfigure;;2;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x1203;AB_ModeFallback;;3;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x1204;AB_ChildNotCommandable;;4;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x1205;AB_NeedToChangeHealth;;5;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h -0x12a1;AB_NotEnoughChildrenInCorrectState;;161;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h +0x3401;DC_NoReplyReceived;;1;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3402;DC_ProtocolError;;2;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3403;DC_Nullpointer;;3;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3404;DC_InvalidCookieType;;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3405;DC_NotActive;;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h +0x3406;DC_TooMuchData;;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h 0x27a0;DHI_NoCommandData;;160;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h 0x27a1;DHI_CommandNotSupported;;161;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h 0x27a2;DHI_CommandAlreadySent;;162;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h @@ -411,58 +440,28 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x27c3;DHI_DeviceReplyInvalid;;195;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h 0x27d0;DHI_InvalidCommandParameter;;208;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h 0x27d1;DHI_InvalidNumberOrLengthOfParameters;;209;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x2401;MT_TooDetailedRequest;;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2402;MT_TooGeneralRequest;;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2403;MT_NoMatch;;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2404;MT_Full;;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2405;MT_NewNodeCreated;;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x3f01;DLEE_NoPacketFound;;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h -0x3f02;DLEE_PossiblePacketLoss;;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h -0x2f01;ASC_TooLongForTargetType;;1;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h -0x2f02;ASC_InvalidCharacters;;2;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h -0x2f03;ASC_BufferTooSmall;;3;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h -0x1701;HHI_ObjectNotHealthy;;1;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h -0x1702;HHI_InvalidHealthState;;2;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h -0x1703;HHI_IsExternallyControlled;;3;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h -0x3201;CF_ObjectHasNoFunctions;;1;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h -0x3202;CF_AlreadyCommanding;;2;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h -0x3301;HF_IsBusy;;1;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x3302;HF_InvalidParameters;;2;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x3303;HF_ExecutionFinished;;3;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x3304;HF_InvalidActionId;;4;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x1000;TIM_UnsupportedTimeFormat;;0;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1001;TIM_NotEnoughInformationForTargetFormat;;1;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1002;TIM_LengthMismatch;;2;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1003;TIM_InvalidTimeFormat;;3;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1004;TIM_InvalidDayOfYear;;4;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x1005;TIM_TimeDoesNotFitFormat;;5;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h -0x3701;TSI_BadTimestamp;;1;TIME_STAMPER_IF;fsfw/src/fsfw/timemanager/TimeStampIF.h -0x3c00;LPIF_PoolEntryNotFound;;0;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h -0x3c01;LPIF_PoolEntryTypeConflict;;1;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h -0x3e00;HKM_QueueOrDestinationInvalid;;0;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e01;HKM_WrongHkPacketType;;1;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e02;HKM_ReportingStatusUnchanged;;2;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e03;HKM_PeriodicHelperInvalid;;3;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e04;HKM_PoolobjectNotFound;;4;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3e05;HKM_DatasetNotFound;;5;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x2901;TC_InvalidTargetState;;1;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h -0x29f1;TC_AboveOperationalLimit;;241;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h -0x29f2;TC_BelowOperationalLimit;;242;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h -0x2001;CSB_ExecutionComplete;;1;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2002;CSB_NoStepMessage;;2;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2003;CSB_ObjectBusy;;3;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2004;CSB_Busy;;4;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2005;CSB_InvalidTc;;5;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2006;CSB_InvalidObject;;6;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x2007;CSB_InvalidReply;;7;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x4c00;SPPA_NoPacketFound;;0;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h -0x4c01;SPPA_SplitPacket;;1;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h -0x1d01;ATC_ActivityStarted;;1;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d02;ATC_InvalidSubservice;;2;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d03;ATC_IllegalApplicationData;;3;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d04;ATC_SendTmFailed;;4;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d05;ATC_Timeout;;5;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x6b00;SCBU_KeyNotFound;;0;SCRATCH_BUFFER;bsp_q7s/memory/scratchApi.h +0x1401;SE_BufferTooShort;;1;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x1402;SE_StreamTooShort;;2;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x1403;SE_TooManyElements;;3;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h +0x4500;HSPI_HalTimeoutRetval;;0;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h +0x4501;HSPI_HalBusyRetval;;1;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h +0x4502;HSPI_HalErrorRetval;;2;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h +0x4601;HURT_UartReadFailure;;1;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h +0x4602;HURT_UartReadSizeMissmatch;;2;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h +0x4603;HURT_UartRxBufferTooSmall;;3;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h +0x4801;HGIO_UnknownGpioId;;1;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4802;HGIO_DriveGpioFailure;;2;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4803;HGIO_GpioTypeFailure;;3;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4804;HGIO_GpioInvalidInstance;;4;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4805;HGIO_GpioDuplicateDetected;;5;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4806;HGIO_GpioInitFailed;;6;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4807;HGIO_GpioGetValueFailed;;7;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h +0x4400;UXOS_ExecutionFinished;Execution of the current command has finished;0;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h +0x4401;UXOS_CommandPending;Command is pending. This will also be returned if the user tries to load another command but a command is still pending;1;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h +0x4402;UXOS_BytesRead;Some bytes have been read from the executing process;2;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h +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;;6;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h 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 0x6a00;SDMA_OpOngoing;;0;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h @@ -475,3 +474,4 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x6a0d;SDMA_UnmountError;;13;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h 0x6a0e;SDMA_SystemCallError;;14;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h 0x6a0f;SDMA_PopenCallError;;15;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h +0x6b00;SCBU_KeyNotFound;;0;SCRATCH_BUFFER;bsp_q7s/memory/scratchApi.h diff --git a/generators/events/translateEvents.cpp b/generators/events/translateEvents.cpp index ee85e05c..fdcc4488 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 234 translations. + * @brief Auto-generated event translation file. Contains 239 translations. * @details - * Generated on: 2022-11-14 17:10:10 + * Generated on: 2022-11-28 18:24:37 */ #include "translateEvents.h" @@ -129,10 +129,13 @@ const char *RESET_OCCURED_STRING = "RESET_OCCURED"; const char *BOOTING_FIRMWARE_FAILED_STRING = "BOOTING_FIRMWARE_FAILED"; const char *BOOTING_BOOTLOADER_FAILED_STRING = "BOOTING_BOOTLOADER_FAILED"; const char *SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING = "SUPV_MEMORY_READ_RPT_CRC_FAILURE"; +const char *SUPV_UNKNOWN_TM_STRING = "SUPV_UNKNOWN_TM"; +const char *SUPV_UNINIMPLEMENTED_TM_STRING = "SUPV_UNINIMPLEMENTED_TM"; const char *SUPV_ACK_FAILURE_STRING = "SUPV_ACK_FAILURE"; const char *SUPV_EXE_FAILURE_STRING = "SUPV_EXE_FAILURE"; const char *SUPV_CRC_FAILURE_EVENT_STRING = "SUPV_CRC_FAILURE_EVENT"; -const char *SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING = "SUPV_MPSOC_SHUWDOWN_BUILD_FAILED"; +const char *SUPV_HELPER_EXECUTING_STRING = "SUPV_HELPER_EXECUTING"; +const char *SUPV_MPSOC_SHUTDOWN_BUILD_FAILED_STRING = "SUPV_MPSOC_SHUTDOWN_BUILD_FAILED"; const char *SANITIZATION_FAILED_STRING = "SANITIZATION_FAILED"; const char *MOUNTED_SD_CARD_STRING = "MOUNTED_SD_CARD"; const char *SEND_MRAM_DUMP_FAILED_STRING = "SEND_MRAM_DUMP_FAILED"; @@ -222,6 +225,8 @@ const char *WRITE_MEMORY_FAILED_STRING = "WRITE_MEMORY_FAILED"; const char *SUPV_REPLY_SIZE_MISSMATCH_STRING = "SUPV_REPLY_SIZE_MISSMATCH"; const char *SUPV_REPLY_CRC_MISSMATCH_STRING = "SUPV_REPLY_CRC_MISSMATCH"; const char *SUPV_UPDATE_PROGRESS_STRING = "SUPV_UPDATE_PROGRESS"; +const char *HDLC_FRAME_REMOVAL_ERROR_STRING = "HDLC_FRAME_REMOVAL_ERROR"; +const char *HDLC_CRC_ERROR_STRING = "HDLC_CRC_ERROR"; const char *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; const char *REBOOT_SW_STRING = "REBOOT_SW"; const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED"; @@ -487,13 +492,19 @@ const char *translateEvents(Event event) { case (12001): return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING; case (12002): - return SUPV_ACK_FAILURE_STRING; + return SUPV_UNKNOWN_TM_STRING; case (12003): - return SUPV_EXE_FAILURE_STRING; + return SUPV_UNINIMPLEMENTED_TM_STRING; case (12004): - return SUPV_CRC_FAILURE_EVENT_STRING; + return SUPV_ACK_FAILURE_STRING; case (12005): - return SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING; + return SUPV_EXE_FAILURE_STRING; + case (12006): + return SUPV_CRC_FAILURE_EVENT_STRING; + case (12007): + return SUPV_HELPER_EXECUTING_STRING; + case (12008): + return SUPV_MPSOC_SHUTDOWN_BUILD_FAILED_STRING; case (12100): return SANITIZATION_FAILED_STRING; case (12101): @@ -672,6 +683,10 @@ const char *translateEvents(Event event) { return SUPV_REPLY_CRC_MISSMATCH_STRING; case (13630): return SUPV_UPDATE_PROGRESS_STRING; + case (13631): + return HDLC_FRAME_REMOVAL_ERROR_STRING; + case (13632): + return HDLC_CRC_ERROR_STRING; case (13700): return ALLOC_FAILURE_STRING; case (13701): diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index 96a2d656..f6e58aab 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 148 translations. - * Generated on: 2022-11-14 17:10:10 + * Generated on: 2022-11-28 18:24:37 */ #include "translateObjects.h" diff --git a/linux/CMakeLists.txt b/linux/CMakeLists.txt index f8c8935f..7f6ea0bc 100644 --- a/linux/CMakeLists.txt +++ b/linux/CMakeLists.txt @@ -9,4 +9,4 @@ if(EIVE_ADD_LINUX_FSFWCONFIG) add_subdirectory(fsfwconfig) endif() -target_sources(${OBSW_NAME} PUBLIC ObjectFactory.cpp InitMission.cpp) +target_sources(${OBSW_NAME} PUBLIC ObjectFactory.cpp scheduling.cpp) diff --git a/linux/devices/ScexUartReader.cpp b/linux/devices/ScexUartReader.cpp index 6f615014..eb61fa2e 100644 --- a/linux/devices/ScexUartReader.cpp +++ b/linux/devices/ScexUartReader.cpp @@ -98,18 +98,11 @@ ReturnValue_t ScexUartReader::initializeInterface(CookieIF *cookie) { } // Setting up UART parameters tty.c_cflag &= ~PARENB; // Clear parity bit - if (uartCookie->getStopBits() == StopBits::TWO_STOP_BITS) { - // Use two stop bits - tty.c_cflag |= CSTOPB; - } else { - // Clear stop field, only one stop bit used in communication - tty.c_cflag &= ~CSTOPB; - } - - tty.c_cflag &= ~CSIZE; // Clear all the size bits - tty.c_cflag |= CS8; // 8 bits per byte - tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control - tty.c_cflag |= CREAD | CLOCAL; // Turn on READ & ignore ctrl lines (CLOCAL = 1) + uart::setStopbits(tty, uartCookie->getStopBits()); + uart::setBitsPerWord(tty, BitsPerWord::BITS_8); + tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control + uart::enableRead(tty); + uart::ignoreCtrlLines(tty); // Use non-canonical mode and clear echo flag tty.c_lflag &= ~(ICANON | ECHO); diff --git a/linux/devices/devicedefinitions/MPSoCReturnValuesIF.h b/linux/devices/devicedefinitions/MPSoCReturnValuesIF.h index 8a1085ca..032211e0 100644 --- a/linux/devices/devicedefinitions/MPSoCReturnValuesIF.h +++ b/linux/devices/devicedefinitions/MPSoCReturnValuesIF.h @@ -1,6 +1,7 @@ #ifndef MPSOC_RETURN_VALUES_IF_H_ #define MPSOC_RETURN_VALUES_IF_H_ +#include "eive/resultClassIds.h" #include "fsfw/returnvalues/returnvalue.h" class MPSoCReturnValuesIF { diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index a5ed0672..8a88a716 100644 --- a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h +++ b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h @@ -153,7 +153,7 @@ class TcBase : public ploc::SpTcBase, public MPSoCReturnValuesIF { */ TcBase(ploc::SpTcParams params, uint16_t apid, uint16_t sequenceCount) : ploc::SpTcBase(params, apid, sequenceCount) { - spParams.setDataFieldLen(INIT_LENGTH); + spParams.setFullPayloadLen(INIT_LENGTH); } ReturnValue_t buildPacket() { return buildPacket(nullptr, 0); } @@ -181,7 +181,7 @@ class TcBase : public ploc::SpTcBase, public MPSoCReturnValuesIF { if (res != returnvalue::OK) { return res; } - return calcCrc(); + return calcAndSetCrc(); } protected: @@ -206,7 +206,7 @@ class TcMemRead : public TcBase { */ TcMemRead(ploc::SpTcParams params, uint16_t sequenceCount) : TcBase(params, apid::TC_MEM_READ, sequenceCount) { - spParams.setPayloadLen(COMMAND_LENGTH); + spParams.setFullPayloadLen(COMMAND_LENGTH + CRC_SIZE); } uint16_t getMemLen() const { return memLen; } @@ -267,7 +267,7 @@ class TcMemWrite : public TcBase { } uint16_t memLen = *(commandData + MEM_ADDRESS_SIZE) << 8 | *(commandData + MEM_ADDRESS_SIZE + 1); - spParams.setPayloadLen(MIN_FIXED_PAYLOAD_LENGTH + memLen * 4); + spParams.setFullPayloadLen(MIN_FIXED_PAYLOAD_LENGTH + memLen * 4 + CRC_SIZE); result = checkPayloadLen(); if (result != returnvalue::OK) { return result; @@ -313,7 +313,7 @@ class FlashFopen : public ploc::SpTcBase { ReturnValue_t createPacket(std::string filename, char accessMode_) { accessMode = accessMode_; size_t nameSize = filename.size(); - spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR) + sizeof(accessMode)); + spParams.setFullPayloadLen(nameSize + sizeof(NULL_TERMINATOR) + sizeof(accessMode) + CRC_SIZE); ReturnValue_t result = checkPayloadLen(); if (result != returnvalue::OK) { return result; @@ -322,7 +322,7 @@ class FlashFopen : public ploc::SpTcBase { *(spParams.buf + nameSize) = NULL_TERMINATOR; std::memcpy(payloadStart + nameSize + sizeof(NULL_TERMINATOR), &accessMode, sizeof(accessMode)); updateSpFields(); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -339,14 +339,14 @@ class FlashFclose : public ploc::SpTcBase { ReturnValue_t createPacket(std::string filename) { size_t nameSize = filename.size(); - spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR)); + spParams.setFullPayloadLen(nameSize + sizeof(NULL_TERMINATOR) + CRC_SIZE); ReturnValue_t result = checkPayloadLen(); if (result != returnvalue::OK) { return result; } std::memcpy(payloadStart, filename.c_str(), nameSize); *(payloadStart + nameSize) = NULL_TERMINATOR; - return calcCrc(); + return calcAndSetCrc(); } }; @@ -365,7 +365,7 @@ class TcFlashWrite : public ploc::SpTcBase { sif::debug << "FlashWrite::createPacket: Command data too big" << std::endl; return returnvalue::FAILED; } - spParams.setPayloadLen(static_cast(writeLen) + 4); + spParams.setFullPayloadLen(static_cast(writeLen) + 4 + CRC_SIZE); result = checkPayloadLen(); if (result != returnvalue::OK) { return result; @@ -382,7 +382,7 @@ class TcFlashWrite : public ploc::SpTcBase { if (res != returnvalue::OK) { return res; } - return calcCrc(); + return calcAndSetCrc(); } private: @@ -399,7 +399,7 @@ class TcFlashDelete : public ploc::SpTcBase { ReturnValue_t buildPacket(std::string filename) { size_t nameSize = filename.size(); - spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR)); + spParams.setFullPayloadLen(nameSize + sizeof(NULL_TERMINATOR) + CRC_SIZE); auto res = checkPayloadLen(); if (res != returnvalue::OK) { return res; @@ -412,7 +412,7 @@ class TcFlashDelete : public ploc::SpTcBase { if (res != returnvalue::OK) { return res; } - return calcCrc(); + return calcAndSetCrc(); } }; @@ -439,7 +439,7 @@ class TcReplayStart : public TcBase { protected: ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override { ReturnValue_t result = returnvalue::OK; - spParams.setPayloadLen(commandDataLen); + spParams.setFullPayloadLen(commandDataLen + CRC_SIZE); result = lengthCheck(commandDataLen); if (result != returnvalue::OK) { return result; @@ -500,7 +500,7 @@ class TcDownlinkPwrOn : public TcBase { if (result != returnvalue::OK) { return result; } - spParams.setPayloadLen(commandDataLen + sizeof(MAX_AMPLITUDE)); + spParams.setFullPayloadLen(commandDataLen + sizeof(MAX_AMPLITUDE) + CRC_SIZE); result = checkPayloadLen(); if (result != returnvalue::OK) { return result; @@ -571,7 +571,7 @@ class TcReplayWriteSeq : public TcBase { protected: ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override { ReturnValue_t result = returnvalue::OK; - spParams.setPayloadLen(commandDataLen + sizeof(NULL_TERMINATOR)); + spParams.setFullPayloadLen(commandDataLen + sizeof(NULL_TERMINATOR) + CRC_SIZE); result = lengthCheck(commandDataLen); if (result != returnvalue::OK) { return result; @@ -657,7 +657,8 @@ class TcCamcmdSend : public TcBase { return INVALID_LENGTH; } uint16_t dataLen = static_cast(commandDataLen + sizeof(CARRIAGE_RETURN)); - spParams.setPayloadLen(sizeof(dataLen) + commandDataLen + sizeof(CARRIAGE_RETURN)); + spParams.setFullPayloadLen(sizeof(dataLen) + commandDataLen + sizeof(CARRIAGE_RETURN) + + CRC_SIZE); auto res = checkPayloadLen(); if (res != returnvalue::OK) { return res; diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 19b224cc..cb0639fa 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -8,13 +8,76 @@ #include #include #include -#include -#include "linux/devices/devicedefinitions/SupvReturnValuesIF.h" +#include + +#include "eive/resultClassIds.h" #include "mission/devices/devicedefinitions/SpBase.h" namespace supv { +namespace result { +static const uint8_t INTERFACE_ID = CLASS_ID::SUPV_RETURN_VALUES_IF; + +//! [EXPORT] : [COMMENT] Space Packet received from PLOC supervisor has invalid CRC +static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xA0); +static constexpr ReturnValue_t INVALID_SERVICE_ID = MAKE_RETURN_CODE(0xA1); +//! [EXPORT] : [COMMENT] Received ACK failure reply from PLOC supervisor +static const ReturnValue_t RECEIVED_ACK_FAILURE = MAKE_RETURN_CODE(0xA2); +//! [EXPORT] : [COMMENT] Received execution failure reply from PLOC supervisor +static const ReturnValue_t RECEIVED_EXE_FAILURE = MAKE_RETURN_CODE(0xA3); +//! [EXPORT] : [COMMENT] Received space packet with invalid APID from PLOC supervisor +static const ReturnValue_t INVALID_APID = MAKE_RETURN_CODE(0xA4); +//! [EXPORT] : [COMMENT] Failed to read current system time +static const ReturnValue_t GET_TIME_FAILURE = MAKE_RETURN_CODE(0xA5); +//! [EXPORT] : [COMMENT] Received command with invalid watchdog parameter. Valid watchdogs are 0 +//! for PS, 1 for PL and 2 for INT +static const ReturnValue_t INVALID_WATCHDOG = MAKE_RETURN_CODE(0xA6); +//! [EXPORT] : [COMMENT] Received watchdog timeout config command with invalid timeout. Valid +//! timeouts must be in the range between 1000 and 360000 ms. +static const ReturnValue_t INVALID_WATCHDOG_TIMEOUT = MAKE_RETURN_CODE(0xA7); +//! [EXPORT] : [COMMENT] Received latchup config command with invalid latchup ID +static const ReturnValue_t INVALID_LATCHUP_ID = MAKE_RETURN_CODE(0xA8); +//! [EXPORT] : [COMMENT] Received set adc sweep period command with invalid sweep period. Must be +//! larger than 21. +static const ReturnValue_t SWEEP_PERIOD_TOO_SMALL = MAKE_RETURN_CODE(0xA9); +//! [EXPORT] : [COMMENT] Receive auto EM test command with invalid test param. Valid params are 1 +//! and 2. +static const ReturnValue_t INVALID_TEST_PARAM = MAKE_RETURN_CODE(0xAA); +//! [EXPORT] : [COMMENT] Returned when scanning for MRAM dump packets failed. +static const ReturnValue_t MRAM_PACKET_PARSING_FAILURE = MAKE_RETURN_CODE(0xAB); +//! [EXPORT] : [COMMENT] Returned when the start and stop addresses of the MRAM dump or MRAM wipe +//! commands are invalid (e.g. start address bigger than stop address) +static const ReturnValue_t INVALID_MRAM_ADDRESSES = MAKE_RETURN_CODE(0xAC); +//! [EXPORT] : [COMMENT] Expect reception of an MRAM dump packet but received space packet with +//! other apid. +static const ReturnValue_t NO_MRAM_PACKET = MAKE_RETURN_CODE(0xAD); +//! [EXPORT] : [COMMENT] Path to PLOC directory on SD card does not exist +static const ReturnValue_t PATH_DOES_NOT_EXIST = MAKE_RETURN_CODE(0xAE); +//! [EXPORT] : [COMMENT] MRAM dump file does not exists. The file should actually already have +//! been created with the reception of the first dump packet. +static const ReturnValue_t MRAM_FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xAF); +static constexpr ReturnValue_t INVALID_REPLY_LENGTH = MAKE_RETURN_CODE(0xB0); +//! [EXPORT] : [COMMENT] Received action command has invalid length +static const ReturnValue_t INVALID_LENGTH = MAKE_RETURN_CODE(0xB1); +//! [EXPORT] : [COMMENT] Filename too long +static const ReturnValue_t FILENAME_TOO_LONG = MAKE_RETURN_CODE(0xB2); +//! [EXPORT] : [COMMENT] Received update status report with invalid packet length field +static const ReturnValue_t UPDATE_STATUS_REPORT_INVALID_LENGTH = MAKE_RETURN_CODE(0xB3); +//! [EXPORT] : [COMMENT] Update status report does not contain expected CRC. There might be a bit +//! flip in the update memory region. +static const ReturnValue_t UPDATE_CRC_FAILURE = MAKE_RETURN_CODE(0xB4); +//! [EXPORT] : [COMMENT] Supervisor helper task ist currently executing a command (wait until +//! helper tas has finished or interrupt by sending the terminate command) +static const ReturnValue_t SUPV_HELPER_EXECUTING = MAKE_RETURN_CODE(0xB5); + +static constexpr ReturnValue_t BUF_TOO_SMALL = MAKE_RETURN_CODE(0xC0); +static constexpr ReturnValue_t NO_REPLY_TIMEOUT = MAKE_RETURN_CODE(0xC1); + +}; // namespace result + +static constexpr uint16_t DEFAULT_SEQ_COUNT = 0; + /** Command IDs */ static const DeviceCommandId_t NONE = 0; static const DeviceCommandId_t GET_HK_REPORT = 1; @@ -41,10 +104,8 @@ static const DeviceCommandId_t FIRST_MRAM_DUMP = 30; static const DeviceCommandId_t SET_GPIO = 34; static const DeviceCommandId_t READ_GPIO = 35; static const DeviceCommandId_t RESTART_SUPERVISOR = 36; -static const DeviceCommandId_t FACTORY_RESET_CLEAR_ALL = 37; static const DeviceCommandId_t LOGGING_REQUEST_COUNTERS = 38; -static const DeviceCommandId_t FACTORY_RESET_CLEAR_MIRROR = 40; -static const DeviceCommandId_t FACTORY_RESET_CLEAR_CIRCULAR = 41; +static constexpr DeviceCommandId_t FACTORY_RESET = 39; static const DeviceCommandId_t CONSECUTIVE_MRAM_DUMP = 43; static const DeviceCommandId_t START_MPSOC_QUIET = 45; static const DeviceCommandId_t SET_SHUTDOWN_TIMEOUT = 46; @@ -61,15 +122,19 @@ static const DeviceCommandId_t RESET_PL = 58; static const DeviceCommandId_t ENABLE_NVMS = 59; static const DeviceCommandId_t CONTINUE_UPDATE = 60; static const DeviceCommandId_t MEMORY_CHECK_WITH_FILE = 61; +static constexpr DeviceCommandId_t MEMORY_CHECK = 62; /** Reply IDs */ -static const DeviceCommandId_t ACK_REPORT = 100; -static const DeviceCommandId_t EXE_REPORT = 101; -static const DeviceCommandId_t HK_REPORT = 102; -static const DeviceCommandId_t BOOT_STATUS_REPORT = 103; -static const DeviceCommandId_t LATCHUP_REPORT = 104; -static const DeviceCommandId_t LOGGING_REPORT = 105; -static const DeviceCommandId_t ADC_REPORT = 106; +enum ReplyId : DeviceCommandId_t { + ACK_REPORT = 100, + EXE_REPORT = 101, + HK_REPORT = 102, + BOOT_STATUS_REPORT = 103, + LATCHUP_REPORT = 104, + LOGGING_REPORT = 105, + ADC_REPORT = 106, + UPDATE_STATUS_REPORT = 107, +}; // Size of complete space packet (6 byte header + size of data + 2 byte CRC) static const uint16_t SIZE_ACK_REPORT = 14; @@ -80,80 +145,199 @@ static const uint16_t SIZE_LATCHUP_STATUS_REPORT = 31; static const uint16_t SIZE_LOGGING_REPORT = 73; static const uint16_t SIZE_ADC_REPORT = 72; -/** - * SpacePacket apids of telemetry packets - */ -static const uint16_t APID_ACK_SUCCESS = 0x200; -static const uint16_t APID_ACK_FAILURE = 0x201; -static const uint16_t APID_EXE_SUCCESS = 0x202; -static const uint16_t APID_EXE_FAILURE = 0x203; -static const uint16_t APID_HK_REPORT = 0x204; -static const uint16_t APID_BOOT_STATUS_REPORT = 0x205; -static const uint16_t APID_UPDATE_STATUS_REPORT = 0x206; -static const uint16_t APID_ADC_REPORT = 0x207; -static const uint16_t APID_LATCHUP_STATUS_REPORT = 0x208; -static const uint16_t APID_SOC_SYSMON = 0x209; -static const uint16_t APID_MRAM_DUMP_TM = 0x20A; -static const uint16_t APID_SRAM = 0x20B; -static const uint16_t APID_NOR_DATA = 0x20C; -static const uint16_t APID_DATA_LOGGER_DATA = 0x20D; - -/** - * APIDs of telecommand packets - */ // 2 bits APID SRC, 00 for OBC, 2 bits APID DEST, 01 for SUPV, 7 bits CMD ID -> Mask 0x080 static constexpr uint16_t APID_TC_SUPV_MASK = 0x080; -static const uint16_t APID_START_MPSOC = 0xA1; -static const uint16_t APID_SHUTWOWN_MPSOC = 0xA2; -static const uint16_t APID_SEL_MPSOC_BOOT_IMAGE = 0xA3; -static const uint16_t APID_SET_BOOT_TIMEOUT = 0xA4; -static const uint16_t APID_SET_MAX_RESTART_TRIES = 0xA5; -static const uint16_t APID_RESET_MPSOC = 0xA6; -static const uint16_t APID_RESET_PL = 0xA7; -static const uint16_t APID_GET_BOOT_STATUS_RPT = 0xA8; -static const uint16_t APID_PREPARE_UPDATE = 0xA9; -static const uint16_t APID_START_MPSOC_QUIET = 0xAA; -static const uint16_t APID_SET_SHUTDOWN_TIMEOUT = 0xAB; -static const uint16_t APID_FACTORY_FLASH = 0xAC; -static const uint16_t APID_ERASE_MEMORY = 0xB0; -static const uint16_t APID_WRITE_MEMORY = 0xB1; -static const uint16_t APID_CHECK_MEMORY = 0xB2; -static const uint16_t APID_SET_TIME_REF = 0xC2; -static const uint16_t APID_DISABLE_HK = 0xC3; -static const uint16_t APID_AUTO_TM = 0xC5; -static const uint16_t APID_ENABLE_LATCHUP_ALERT = 0xD0; -static const uint16_t APID_DISABLE_LATCHUP_ALERT = 0xD1; -static const uint16_t APID_SET_ALERT_LIMIT = 0xD3; -static const uint16_t APID_SET_ADC_ENABLED_CHANNELS = 0xE1; -static const uint16_t APID_SET_ADC_WINDOW_AND_STRIDE = 0xE2; -static const uint16_t APID_SET_ADC_THRESHOLD = 0xE3; -static const uint16_t APID_GET_LATCHUP_STATUS_REPORT = 0xD9; -static const uint16_t APID_COPY_ADC_DATA_TO_MRAM = 0xDA; -static const uint16_t APID_REQUEST_ADC_REPORT = 0xDB; -static const uint16_t APID_ENABLE_NVMS = 0xF0; -static const uint16_t APID_RUN_AUTO_EM_TESTS = 0xF2; -static const uint16_t APID_WIPE_MRAM = 0xF3; -static const uint16_t APID_DUMP_MRAM = 0xF4; -static const uint16_t APID_SET_GPIO = 0xF9; -static const uint16_t APID_READ_GPIO = 0xFA; -static const uint16_t APID_RESTART_SUPERVISOR = 0xFB; -static const uint16_t APID_FACTORY_RESET = 0xFC; -static const uint16_t APID_REQUEST_LOGGING_DATA = 0xFD; +enum Apid { + TMTC_MAN = 0x00, + HK = 0x01, + BOOT_MAN = 0x02, + LATCHUP_MON = 0x03, + ADC_MON = 0x04, + MEM_MAN = 0x05, + DATA_LOGGER = 0x06, + WDOG_MAN = 0x07 +}; -static const uint16_t APID_GET_HK_REPORT = 0xC6; +namespace tc { -static const uint16_t APID_MASK = 0x3FF; +enum class HkId : uint8_t { + ENABLE = 0x01, + SET_PERIOD = 0x02, + GET_REPORT = 0x03, + GET_HARDFAULTS_REPORT = 0x04, +}; + +enum class TmtcId : uint8_t { + TIME_REF = 0x03, + GET_SUPV_VERSION = 0x05, + RUN_AUTO_EM_TEST = 0x08, + SET_GPIO = 0x0E, + READ_GPIO = 0x0F, + GET_MPSOC_POWER_INFO = 0x10 +}; + +enum class BootManId : uint8_t { + START_MPSOC = 0x01, + SHUTDOWN_MPSOC = 0x02, + SELECT_IMAGE = 0x03, + SET_BOOT_TIMEOUT = 0x04, + SET_MAX_REBOOT_TRIES = 0x05, + RESET_MPSOC = 0x06, + RESET_PL = 0x07, + GET_BOOT_STATUS_REPORT = 0x08, + PREPARE_UPDATE = 0x09, + SHUTDOWN_TIMEOUT = 0x0B, + FACTORY_FLASH = 0x0C +}; + +enum class LatchupMonId : uint8_t { + ENABLE = 0x01, + DISABLE = 0x02, + SET_ALERT_LIMIT = 0x04, + GET_STATUS_REPORT = 0x06 +}; + +// Right now, none of the commands seem to be implemented, but still +// keep the enum here in case some are added +enum class AdcMonId : uint8_t { + SET_SWEEP_PERIOD = 0x01, + SET_ENABLED_CHANNELS = 0x02, + SET_WINDOW_STRIDE = 0x03, + SET_ADC_THRESHOLD = 0x04, + COPY_ADC_DATA_TO_MRAM = 0x05 +}; + +enum class MemManId : uint8_t { ERASE = 0x01, WRITE = 0x02, CHECK = 0x03 }; + +enum class DataLoggerServiceId : uint8_t { + WIPE_MRAM = 0x05, + DUMP_MRAM = 0x06, + FACTORY_RESET = 0x07 +}; + +// Right now, none of the commands seem to be implemented, but still +// keep the enum here in case some are added +enum class WdogManServiceId : uint8_t {}; + +} // namespace tc + +namespace tm { + +enum class TmtcId : uint8_t { ACK = 0x01, NAK = 0x02, EXEC_ACK = 0x03, EXEC_NAK = 0x04 }; + +enum class HkId : uint8_t { REPORT = 0x01, HARDFAULTS = 0x02 }; + +enum class BootManId : uint8_t { BOOT_STATUS_REPORT = 0x01 }; + +enum class MemManId : uint8_t { UPDATE_STATUS_REPORT = 0x01 }; + +enum class LatchupMonId : uint8_t { LATCHUP_STATUS_REPORT = 0x01 }; + +} // namespace tm + +enum class GeneralStatusCode : uint32_t { + OK = 0x000, + NAK = 0x001, + INIT_ERROR = 0x002, + BAD_PARAM = 0x003, + NOT_INITIALIZED = 0x004, + BAD_PERIPH_ID = 0x005, + TIMEOUT = 0x006, + RX_ERROR = 0x007, + TX_ERROR = 0x008, + ARB_LOST = 0x009, + BUSY = 0x00A, + NOT_IMPL = 0x00B, + ALIGNMENT_ERROR = 0x00C, + PERIPH_ERROR = 0x00D, + FAILED_LATCH = 0x00E, + GPIO_HIGH = 0x00F, + GPIO_LOW = 0x010, + TEST_PASSED = 0x011, + TEST_FAILED = 0x012, + BAD_NOF_PARAMS = 0x013, + NULL_POINTER = 0x014, + TASK_CREATION_ERROR = 0x015, + CORRUPTED_MRAM_VAL = 0x016, + BUF_EMPTY = 0x017 +}; + +enum class BootManStatusCode : uint32_t { + NOTHING_TODO = 0x100, + POWER_FAULT = 0x101, + INVALID_LENGTH = 0x102, + OUT_OF_RANGE = 0x103, + OUT_OF_HEAP_MEMORY = 0x104, + INVALID_STATE_TRANSITION = 0x105, + MPSOC_ALREADY_BOOTING = 0x106, + MPSOC_ALREADY_OPERATIONAL = 0x107, + MPSOC_BOOT_FAILED = 0x108, +}; + +enum class MemManStatusCode : uint32_t { + SP_NOT_AVAILABLE = 0x200, + SP_DATA_INSUFFICIENT = 0x201, + SP_MEMORY_ID_INVALID = 0x202, + MPSOC_NOT_IN_RESET = 0x203, + FLASH_INIT_FAILED = 0x204, + FLASH_ERASE_FAILED = 0x205, + FLASH_WRITE_FAILED = 0x206, + FLASH_VERIFY_FAILED = 0x207, + CANNOT_ACCESS_TM = 0x208, + CANNOT_SEND_TM = 0x209, +}; + +enum class PowerManStatusCode : uint32_t { + PG_LOW = 0x300, + PG_5V_LOW = 0x301, + PG_0V85_LOW = 0x302, + PG_1V8_LOW = 0x303, + PG_MISC_LOW = 0x304, + PG_3V3_LOW = 0x305, + PG_MB_VAIO_LOW = 0x306, + PG_MB_MPSOCIO_LOW = 0x307 +}; + +enum class TmtcManStatusCode : uint32_t { + BUF_FULL = 0x600, + WRONG_APID = 0x601, + WRONG_SERVICE_ID = 0x602, + TC_DELIVERY_ACCEPTED = 0x603, + TC_DELIVERY_REJECTED = 0x0604, + TC_PACKET_LEN_INCORRECT = 0x605, + BAD_CRC = 0x606, + BAD_DEST = 0x607, + BAD_SP_HEADER = 0x608 +}; + +static constexpr uint16_t APID_MASK_TC = 0x80; +static constexpr uint16_t APID_MASK_TM = 0x200; +static constexpr uint16_t APID_MODULE_MASK = 0x7F; static const uint16_t SEQUENCE_COUNT_MASK = 0xFFF; -/** Offset from first byte in Space packet to first byte of data field */ -static const uint8_t DATA_FIELD_OFFSET = 6; +static const uint8_t HK_SET_ENTRIES = 13; +static const uint8_t BOOT_REPORT_SET_ENTRIES = 10; +static const uint8_t LATCHUP_RPT_SET_ENTRIES = 16; +static const uint8_t LOGGING_RPT_SET_ENTRIES = 16; +static const uint8_t ADC_RPT_SET_ENTRIES = 32; -/** - * Space packet length for fixed size packets. This is the size of the whole packet data - * field. For the length field in the space packet this size will be substracted by one. - */ -static const uint16_t LENGTH_EMPTY_TC = 2; // Only CRC will be transported with the data field +static const uint32_t HK_SET_ID = HK_REPORT; +static const uint32_t BOOT_REPORT_SET_ID = BOOT_STATUS_REPORT; +static const uint32_t LATCHUP_RPT_ID = LATCHUP_REPORT; +static const uint32_t LOGGING_RPT_ID = LOGGING_REPORT; +static const uint32_t ADC_REPORT_SET_ID = ADC_REPORT; + +namespace timeout { +// Erase memory can require up to 60 seconds for execution +static const uint32_t ERASE_MEMORY = 60000; +static const uint32_t UPDATE_STATUS_REPORT = 70000; +static const uint32_t CRC_EXECUTION_TIMEOUT = 60000; +} // namespace timeout + +static constexpr size_t TIMESTAMP_LEN = 7; +static constexpr size_t SECONDARY_HEADER_LEN = TIMESTAMP_LEN + 1; +static constexpr size_t CRC_LEN = 2; /** This is the maximum length of a space packet as defined by the TAS ICD */ static const size_t MAX_COMMAND_SIZE = 1024; @@ -161,7 +345,24 @@ static const size_t MAX_DATA_CAPACITY = 1016; /** This is the maximum size of a space packet for the supervisor */ static const size_t MAX_PACKET_SIZE = 1024; -static const uint8_t SPACE_PACKET_HEADER_LENGTH = 6; +static constexpr size_t MIN_PAYLOAD_LEN = SECONDARY_HEADER_LEN + CRC_LEN; +static constexpr size_t MIN_TMTC_LEN = ccsds::HEADER_LEN + MIN_PAYLOAD_LEN; +static constexpr size_t PAYLOAD_OFFSET = ccsds::HEADER_LEN + SECONDARY_HEADER_LEN; + +enum class FactoryResetSelect : uint8_t { + EVENT_BUF = 0x00, + ADC_BUF = 0x01, + SYS_CFG = 0x02, + DEBUG_CFG = 0x03, + BOOT_MAN_CFG = 0x04, + DATA_LOGGER_CFG = 0x05, + DATA_LOGGER_OP_DATA = 0x06, + LATCHUP_MON_CFG = 0x07, + ADC_MON_CFG = 0x08, + WDOG_MAN_CFG = 0x09, + HK_CFG = 0x0A, + MEM_MAN_CFG = 0xB9 +}; struct UpdateParams { std::string file; @@ -265,48 +466,116 @@ enum PoolIds : lp_id_t { ADC_ENG_15 }; -static constexpr uint16_t DEFAULT_SEQUENCE_COUNT = 1; -static const uint8_t HK_SET_ENTRIES = 13; -static const uint8_t BOOT_REPORT_SET_ENTRIES = 10; -static const uint8_t LATCHUP_RPT_SET_ENTRIES = 16; -static const uint8_t LOGGING_RPT_SET_ENTRIES = 16; -static const uint8_t ADC_RPT_SET_ENTRIES = 32; - -static const uint32_t HK_SET_ID = HK_REPORT; -static const uint32_t BOOT_REPORT_SET_ID = BOOT_STATUS_REPORT; -static const uint32_t LATCHUP_RPT_ID = LATCHUP_REPORT; -static const uint32_t LOGGING_RPT_ID = LOGGING_REPORT; -static const uint32_t ADC_REPORT_SET_ID = ADC_REPORT; - -namespace recv_timeout { -// Erase memory can require up to 60 seconds for execution -static const uint32_t ERASE_MEMORY = 60000; -static const uint32_t UPDATE_STATUS_REPORT = 70000; -} // namespace recv_timeout - -/** - * @brief This class creates a space packet containing only the header data and the CRC. - */ -class ApidOnlyPacket : public ploc::SpTcBase { +struct TcParams : public ploc::SpTcParams { public: - /** - * @brief Constructor - * - * @param apid The APID to set in the space packet. - * - * @note Sequence count of empty packet is always 1. - */ - ApidOnlyPacket(ploc::SpTcParams params, uint16_t apid) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(LENGTH_EMPTY_TC); - spParams.creator.setApid(apid); + TcParams(SpacePacketCreator& creator) : ploc::SpTcParams(creator) {} + + TcParams(SpacePacketCreator& creator, uint8_t* buf, size_t maxSize) + : ploc::SpTcParams(creator, buf, maxSize) {} + + void setLenFromPayloadLen(size_t payloadLen) { + setFullPayloadLen(ccsds::HEADER_LEN + SECONDARY_HEADER_LEN + payloadLen + CRC_LEN); + } +}; + +class TcBase : public ploc::SpTcBase { + public: + TcBase(TcParams params) : TcBase(params, 0x00, 0x00, MIN_PAYLOAD_LEN) {} + + TcBase(TcParams params, uint16_t apid) : TcBase(params, apid, 0x00, MIN_PAYLOAD_LEN) {} + + TcBase(TcParams params, uint16_t apid, uint8_t service, size_t payloadLen) + : TcBase(params, apid, service, payloadLen, DEFAULT_SEQ_COUNT) {} + + TcBase(TcParams params, uint16_t apid, uint8_t serviceId, size_t payloadLen, uint16_t seqCount) + : ploc::SpTcBase(params, apid | APID_MASK_TC, fullSpDataLenFromPayloadLen(payloadLen), + seqCount) { + setup(serviceId); } - ReturnValue_t buildPacket() { - auto res = checkSizeAndSerializeHeader(); - if (res != returnvalue::OK) { - return res; + void setServiceId(uint8_t id) { + if (spParams.maxSize < MIN_PAYLOAD_LEN) { + return; } - return calcCrc(); + payloadStart[supv::PAYLOAD_OFFSET] = id; + } + + uint16_t getModuleApid() const { return getApid() & APID_MODULE_MASK; } + + uint8_t getServiceId() const { return getPacketData()[TIMESTAMP_LEN]; } + + static size_t fullSpDataLenFromPayloadLen(size_t payloadLen) { + return SECONDARY_HEADER_LEN + payloadLen + CRC_LEN; + } + + void setLenFromPayloadLen(size_t payloadLen) { + spParams.setFullPayloadLen(fullSpDataLenFromPayloadLen(payloadLen)); + updateLenFromParams(); + } + + private: + ReturnValue_t setup(uint8_t serviceId) { + if (spParams.maxSize < MIN_PAYLOAD_LEN) { + sif::error << "SupvTcBase::SupvTcBase: Passed buffer is too small" << std::endl; + return returnvalue::FAILED; + } + std::memset(spParams.buf + ccsds::HEADER_LEN, 0, TIMESTAMP_LEN); + payloadStart = spParams.buf + ccsds::HEADER_LEN + SECONDARY_HEADER_LEN; + spParams.buf[ccsds::HEADER_LEN + SECONDARY_HEADER_LEN - 1] = serviceId; + spParams.creator.setSecHeaderFlag(); + return returnvalue::OK; + } +}; + +class TmBase : public ploc::SpTmReader { + public: + TmBase() = default; + + TmBase(const uint8_t* data, size_t maxSize) : ploc::SpTmReader(data, maxSize) { + if (maxSize < MIN_TMTC_LEN) { + sif::error << "SupvTcBase::SupvTcBase: Passed buffer is too small" << std::endl; + } + } + + bool verifyCrc() { + if (checkCrc() == returnvalue::OK) { + crcOk = true; + } + return crcOk; + } + + bool crcIsOk() const { return crcOk; } + + uint8_t getServiceId() const { return getPacketData()[TIMESTAMP_LEN]; } + + uint16_t getModuleApid() const { return getApid() & APID_MODULE_MASK; } + + const uint8_t* getPayloadStart() const { return getPacketData() + SECONDARY_HEADER_LEN; } + size_t getPayloadLen() const { + if (getFullPacketLen() > SECONDARY_HEADER_LEN + ccsds::HEADER_LEN) { + return getFullPacketLen() - SECONDARY_HEADER_LEN - ccsds::HEADER_LEN; + } + return 0; + } + + private: + bool crcOk = false; +}; + +class NoPayloadPacket : public TcBase { + public: + NoPayloadPacket(TcParams params, uint16_t apid, uint8_t serviceId) + : NoPayloadPacket(params, apid, serviceId, 0) {} + + NoPayloadPacket(TcParams params, uint16_t apid, uint8_t serviceId, uint16_t seqId) + : TcBase(params, apid, serviceId, MIN_PAYLOAD_LEN, seqId) {} + + ReturnValue_t buildPacket() { + ReturnValue_t result = checkSizeAndSerializeHeader(); + if (result != returnvalue::OK) { + return result; + } + return calcAndSetCrc(); } private: @@ -316,7 +585,7 @@ class ApidOnlyPacket : public ploc::SpTcBase { * @brief This class can be used to generate the space packet selecting the boot image of * of the MPSoC. */ -class MPSoCBootSelect : public ploc::SpTcBase { +class MPSoCBootSelect : public TcBase { public: static const uint8_t NVM0 = 0; static const uint8_t NVM1 = 1; @@ -331,11 +600,8 @@ class MPSoCBootSelect : public ploc::SpTcBase { * * @note Selection of partitions is currently not supported. */ - MPSoCBootSelect(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SEL_MPSOC_BOOT_IMAGE); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + MPSoCBootSelect(TcParams params) + : TcBase(params, Apid::BOOT_MAN, static_cast(tc::BootManId::SELECT_IMAGE), 4) {} ReturnValue_t buildPacket(uint8_t mem = 0, uint8_t bp0 = 0, uint8_t bp1 = 0, uint8_t bp2 = 0) { auto res = checkSizeAndSerializeHeader(); @@ -343,75 +609,26 @@ class MPSoCBootSelect : public ploc::SpTcBase { return res; } initPacket(mem, bp0, bp1, bp2); - return calcCrc(); + return calcAndSetCrc(); } private: - static const uint16_t DATA_FIELD_LENGTH = 6; - - static const uint8_t MEM_OFFSET = 0; - static const uint8_t BP0_OFFSET = 1; - static const uint8_t BP1_OFFSET = 2; - static const uint8_t BP2_OFFSET = 3; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - void initPacket(uint8_t mem = 0, uint8_t bp0 = 0, uint8_t bp1 = 0, uint8_t bp2 = 0) { - std::memcpy(payloadStart + MEM_OFFSET, &mem, sizeof(mem)); - std::memcpy(payloadStart + BP0_OFFSET, &bp0, sizeof(bp0)); - std::memcpy(payloadStart + BP1_OFFSET, &bp1, sizeof(bp1)); - std::memcpy(payloadStart + BP2_OFFSET, &bp2, sizeof(bp2)); - } -}; - -/** - * @brief This class creates the command to enable or disable the NVMs connected to the - * supervisor. - */ -class EnableNvms : public ploc::SpTcBase { - public: - /** - * @brief Constructor - * - * @param mem The memory to boot from: NVM0 (0), NVM1 (1) - * @param bp0 Partition pin 0 - * @param bp1 Partition pin 1 - * @param bp2 Partition pin 2 - */ - EnableNvms(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_ENABLE_NVMS); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } - - ReturnValue_t buildPacket(uint8_t nvm01, uint8_t nvm3) { - auto res = checkSizeAndSerializeHeader(); - if (res != returnvalue::OK) { - return res; - } - initPacket(nvm01, nvm3); - return calcCrc(); - } - - private: - static const uint8_t DATA_FIELD_LENGTH = 4; - static const uint8_t CRC_OFFSET = 2; - - void initPacket(uint8_t nvm01, uint8_t nvm3) { - payloadStart[0] = nvm01; - payloadStart[1] = nvm3; + payloadStart[0] = mem; + payloadStart[1] = bp0; + payloadStart[2] = bp1; + payloadStart[3] = bp2; } }; /** * @brief This class generates the space packet to update the time of the PLOC supervisor. */ -class SetTimeRef : public ploc::SpTcBase { +class SetTimeRef : public TcBase { public: - SetTimeRef(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_TIME_REF); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + static constexpr size_t PAYLOAD_LEN = 8; + SetTimeRef(TcParams params) + : TcBase(params, Apid::TMTC_MAN, static_cast(tc::TmtcId::TIME_REF), 8) {} ReturnValue_t buildPacket(Clock::TimeOfDay_t* time) { auto res = checkSizeAndSerializeHeader(); @@ -422,12 +639,10 @@ class SetTimeRef : public ploc::SpTcBase { if (res != returnvalue::OK) { return res; } - return calcCrc(); + return calcAndSetCrc(); } private: - static const uint16_t DATA_FIELD_LENGTH = 10; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; static const uint16_t SYNC = 0x8000; ReturnValue_t initPacket(Clock::TimeOfDay_t* time) { @@ -479,18 +694,17 @@ class SetTimeRef : public ploc::SpTcBase { /** * @brief This class can be used to generate the set boot timout command. */ -class SetBootTimeout : public ploc::SpTcBase { +class SetBootTimeout : public TcBase { public: + static constexpr size_t PAYLOAD_LEN = 4; /** * @brief Constructor * * @param timeout The boot timeout in milliseconds. */ - SetBootTimeout(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_BOOT_TIMEOUT); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetBootTimeout(TcParams params) + : TcBase(params, Apid::BOOT_MAN, static_cast(tc::BootManId::SET_BOOT_TIMEOUT), + PAYLOAD_LEN) {} ReturnValue_t buildPacket(uint32_t timeout) { auto res = checkSizeAndSerializeHeader(); @@ -498,13 +712,10 @@ class SetBootTimeout : public ploc::SpTcBase { return res; } initPacket(timeout); - return calcCrc(); + return calcAndSetCrc(); } private: - /** boot timeout value (uint32_t) and crc (uint16_t) */ - static const uint16_t DATA_FIELD_LENGTH = 6; - void initPacket(uint32_t timeout) { size_t serializedSize = 0; uint8_t* dataFieldPtr = payloadStart; @@ -513,21 +724,42 @@ class SetBootTimeout : public ploc::SpTcBase { } }; +class FactoryReset : public TcBase { + public: + FactoryReset(TcParams params) + : TcBase(params, Apid::DATA_LOGGER, + static_cast(tc::DataLoggerServiceId::FACTORY_RESET), 0) {} + + ReturnValue_t buildPacket(std::optional op) { + if (op) { + setLenFromPayloadLen(1); + } + auto res = checkSizeAndSerializeHeader(); + if (res != returnvalue::OK) { + return res; + } + if (op) { + payloadStart[0] = op.value(); + } + return calcAndSetCrc(); + } + + private: +}; + /** * @brief This class can be used to generate the space packet to set the maximum boot tries. */ -class SetRestartTries : public ploc::SpTcBase { +class SetRestartTries : public TcBase { public: /** * @brief Constructor * * @param restartTries Maximum restart tries to set. */ - SetRestartTries(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_MAX_RESTART_TRIES); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetRestartTries(TcParams params) + : TcBase(params, Apid::BOOT_MAN, static_cast(tc::BootManId::SET_MAX_REBOOT_TRIES), + 1) {} ReturnValue_t buildPacket(uint8_t restartTries) { auto res = checkSizeAndSerializeHeader(); @@ -535,15 +767,12 @@ class SetRestartTries : public ploc::SpTcBase { return res; } initPacket(restartTries); - return calcCrc(); + return calcAndSetCrc(); } private: uint8_t restartTries = 0; - /** Restart tries value (uint8_t) and crc (uint16_t) */ - static const uint16_t DATA_FIELD_LENGTH = 3; - void initPacket(uint8_t restartTries) { payloadStart[0] = restartTries; } }; @@ -552,16 +781,13 @@ class SetRestartTries : public ploc::SpTcBase { * of housekeeping data. Normally, this will be disabled by default. However, adding this * command can be useful for debugging. */ -class DisablePeriodicHkTransmission : public ploc::SpTcBase { +class DisablePeriodicHkTransmission : public TcBase { public: /** * @brief Constructor */ - DisablePeriodicHkTransmission(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_DISABLE_HK); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + DisablePeriodicHkTransmission(TcParams params) + : TcBase(params, Apid::HK, static_cast(tc::HkId::ENABLE), 1) {} ReturnValue_t buildPacket() { auto res = checkSizeAndSerializeHeader(); @@ -569,13 +795,10 @@ class DisablePeriodicHkTransmission : public ploc::SpTcBase { return res; } initPacket(); - return calcCrc(); + return calcAndSetCrc(); } private: - /** Restart tries value (uint8_t) and crc (uint16_t) */ - static const uint16_t DATA_FIELD_LENGTH = 3; - void initPacket() { payloadStart[0] = false; } }; @@ -584,7 +807,7 @@ class DisablePeriodicHkTransmission : public ploc::SpTcBase { * * @details There are 7 different latchup alerts. */ -class LatchupAlert : public ploc::SpTcBase { +class LatchupAlert : public TcBase { public: /** * @brief Constructor @@ -593,36 +816,29 @@ class LatchupAlert : public ploc::SpTcBase { * @param latchupId Identifies the latchup to enable/disable (0 - 0.85V, 1 - 1.8V, 2 - MISC, * 3 - 3.3V, 4 - NVM_4XO, 5 - MISSION, 6 - SAFECOTS) */ - LatchupAlert(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + LatchupAlert(TcParams params) : TcBase(params, Apid::LATCHUP_MON) { setLenFromPayloadLen(1); } ReturnValue_t buildPacket(bool state, uint8_t latchupId) { if (state) { - spParams.creator.setApid(APID_ENABLE_LATCHUP_ALERT); + setServiceId(static_cast(tc::LatchupMonId::ENABLE)); } else { - spParams.creator.setApid(APID_DISABLE_LATCHUP_ALERT); + setServiceId(static_cast(tc::LatchupMonId::DISABLE)); } auto res = checkSizeAndSerializeHeader(); if (res != returnvalue::OK) { return res; } initPacket(latchupId); - return calcCrc(); + return calcAndSetCrc(); } private: - static const uint16_t DATA_FIELD_LENGTH = 3; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - uint8_t latchupId = 0; void initPacket(uint8_t latchupId) { payloadStart[0] = latchupId; } }; -class SetAlertlimit : public ploc::SpTcBase { +class SetAlertlimit : public TcBase { public: /** * @brief Constructor @@ -631,11 +847,9 @@ class SetAlertlimit : public ploc::SpTcBase { * 3 - 3.3V, 4 - NVM_4XO, 5 - MISSION, 6 - SAFECOTS) * @param dutycycle */ - SetAlertlimit(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_ALERT_LIMIT); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetAlertlimit(TcParams params) + : TcBase(params, Apid::LATCHUP_MON, static_cast(tc::LatchupMonId::SET_ALERT_LIMIT), + 5) {} ReturnValue_t buildPacket(uint8_t latchupId, uint32_t dutycycle) { auto res = checkSizeAndSerializeHeader(); @@ -646,13 +860,10 @@ class SetAlertlimit : public ploc::SpTcBase { if (res != returnvalue::OK) { return res; } - return calcCrc(); + return calcAndSetCrc(); } private: - static const uint16_t DATA_FIELD_LENGTH = 7; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - uint8_t latchupId = 0; uint32_t dutycycle = 0; @@ -664,48 +875,11 @@ class SetAlertlimit : public ploc::SpTcBase { } }; -/** - * @brief This class packages the space packet to enable or disable ADC channels. - */ -class SetAdcEnabledChannels : public ploc::SpTcBase { - public: - /** - * @brief Constructor - * - * @param ch Defines channels to be enabled or disabled. - */ - SetAdcEnabledChannels(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_ADC_ENABLED_CHANNELS); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } - - ReturnValue_t buildPacket(uint16_t ch) { - auto res = checkSizeAndSerializeHeader(); - if (res != returnvalue::OK) { - return res; - } - initPacket(ch); - return calcCrc(); - } - - private: - static const uint16_t DATA_FIELD_LENGTH = 4; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - void initPacket(uint16_t ch) { - size_t serializedSize = 0; - SerializeAdapter::serialize(&ch, &payloadStart, &serializedSize, sizeof(ch), - SerializeIF::Endianness::BIG); - } -}; - /** * @brief This class packages the space packet to configures the window size and striding step of * the moving average filter applied to the ADC readings. */ -class SetAdcWindowAndStride : public ploc::SpTcBase { +class SetAdcWindowAndStride : public TcBase { public: /** * @brief Constructor @@ -713,11 +887,8 @@ class SetAdcWindowAndStride : public ploc::SpTcBase { * @param windowSize * @param stridingStepSize */ - SetAdcWindowAndStride(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_ADC_WINDOW_AND_STRIDE); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetAdcWindowAndStride(TcParams params) + : TcBase(params, Apid::ADC_MON, static_cast(tc::AdcMonId::SET_WINDOW_STRIDE), 4) {} ReturnValue_t buildPacket(uint16_t windowSize, uint16_t stridingStepSize) { auto res = checkSizeAndSerializeHeader(); @@ -725,14 +896,10 @@ class SetAdcWindowAndStride : public ploc::SpTcBase { return res; } initPacket(windowSize, stridingStepSize); - return calcCrc(); + return calcAndSetCrc(); } private: - static const uint16_t DATA_FIELD_LENGTH = 6; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - void initPacket(uint16_t windowSize, uint16_t stridingStepSize) { size_t serializedSize = 6; uint8_t* data = payloadStart; @@ -746,18 +913,15 @@ class SetAdcWindowAndStride : public ploc::SpTcBase { /** * @brief This class packages the space packet to set the ADC trigger threshold. */ -class SetAdcThreshold : public ploc::SpTcBase { +class SetAdcThreshold : public TcBase { public: /** * @brief Constructor * * @param threshold */ - SetAdcThreshold(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_ADC_THRESHOLD); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetAdcThreshold(TcParams params) + : TcBase(params, Apid::ADC_MON, static_cast(tc::AdcMonId::SET_ADC_THRESHOLD), 4) {} ReturnValue_t buildPacket(uint32_t threshold) { auto res = checkSizeAndSerializeHeader(); @@ -765,15 +929,10 @@ class SetAdcThreshold : public ploc::SpTcBase { return res; } initPacket(threshold); - return calcCrc(); + return calcAndSetCrc(); } private: - static const uint16_t DATA_FIELD_LENGTH = 6; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - void initPacket(uint32_t threshold) { size_t serializedSize = 0; SerializeAdapter::serialize(&threshold, payloadStart, &serializedSize, sizeof(threshold), @@ -784,18 +943,15 @@ class SetAdcThreshold : public ploc::SpTcBase { /** * @brief This class packages the space packet to run auto EM tests. */ -class RunAutoEmTests : public ploc::SpTcBase { +class RunAutoEmTests : public TcBase { public: /** * @brief Constructor * * @param test 1 - complete EM test, 2 - Short test (only memory readback NVM0,1,3) */ - RunAutoEmTests(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_RUN_AUTO_EM_TESTS); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + RunAutoEmTests(TcParams params) + : TcBase(params, Apid::TMTC_MAN, static_cast(tc::TmtcId::RUN_AUTO_EM_TEST), 1) {} ReturnValue_t buildPacket(uint8_t test) { auto res = checkSizeAndSerializeHeader(); @@ -803,74 +959,43 @@ class RunAutoEmTests : public ploc::SpTcBase { return res; } initPacket(test); - return calcCrc(); + return calcAndSetCrc(); } private: - static const uint16_t DATA_FIELD_LENGTH = 3; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - uint8_t test = 0; void initPacket(uint8_t test) { payloadStart[0] = test; } }; /** - * @brief This class packages the space packet to wipe or dump parts of the MRAM. + * @brief This class packages the space packet to enable or disable ADC channels. */ -class MramCmd : public ploc::SpTcBase { +class SetAdcEnabledChannels : public TcBase { public: - enum class MramAction { WIPE, DUMP }; - /** * @brief Constructor * - * @param start Start address of the MRAM section to wipe or dump - * @param stop End address of the MRAM section to wipe or dump - * @param action Dump or wipe MRAM - * - * @note The content at the stop address is excluded from the dump or wipe operation. + * @param ch Defines channels to be enabled or disabled. */ - MramCmd(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + SetAdcEnabledChannels(TcParams params) + : TcBase(params, Apid::ADC_MON, static_cast(tc::AdcMonId::SET_ENABLED_CHANNELS), 2) { } - ReturnValue_t buildPacket(uint32_t start, uint32_t stop, MramAction action) { - if (action == MramAction::WIPE) { - spParams.creator.setApid(APID_WIPE_MRAM); - } else if (action == MramAction::DUMP) { - spParams.creator.setApid(APID_DUMP_MRAM); - } else { - sif::debug << "WipeMram: Invalid action specified"; - } + ReturnValue_t buildPacket(uint16_t ch) { auto res = checkSizeAndSerializeHeader(); if (res != returnvalue::OK) { return res; } - initPacket(start, stop); - return calcCrc(); + initPacket(ch); + return calcAndSetCrc(); } private: - static const uint16_t DATA_FIELD_LENGTH = 8; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - - uint32_t start = 0; - uint32_t stop = 0; - - void initPacket(uint32_t start, uint32_t stop) { - uint8_t concatBuffer[6]; - concatBuffer[0] = static_cast(start >> 16); - concatBuffer[1] = static_cast(start >> 8); - concatBuffer[2] = static_cast(start); - concatBuffer[3] = static_cast(stop >> 16); - concatBuffer[4] = static_cast(stop >> 8); - concatBuffer[5] = static_cast(stop); - std::memcpy(payloadStart, concatBuffer, sizeof(concatBuffer)); + void initPacket(uint16_t ch) { + size_t serializedSize = 0; + SerializeAdapter::serialize(&ch, &payloadStart, &serializedSize, sizeof(ch), + SerializeIF::Endianness::BIG); } }; @@ -878,7 +1003,7 @@ class MramCmd : public ploc::SpTcBase { * @brief This class packages the space packet change the state of a GPIO. This command is only * required for ground testing. */ -class SetGpio : public ploc::SpTcBase { +class SetGpio : public TcBase { public: /** * @brief Constructor @@ -887,11 +1012,8 @@ class SetGpio : public ploc::SpTcBase { * @param pin * @param val */ - SetGpio(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_GPIO); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetGpio(TcParams params) + : TcBase(params, Apid::TMTC_MAN, static_cast(tc::TmtcId::SET_GPIO), 3) {} ReturnValue_t buildPacket(uint8_t port, uint8_t pin, uint8_t val) { auto res = checkSizeAndSerializeHeader(); @@ -899,15 +1021,10 @@ class SetGpio : public ploc::SpTcBase { return res; } initPacket(port, pin, val); - return calcCrc(); + return calcAndSetCrc(); } private: - static const uint16_t DATA_FIELD_LENGTH = 5; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - uint8_t port = 0; uint8_t pin = 0; uint8_t val = 0; @@ -923,7 +1040,7 @@ class SetGpio : public ploc::SpTcBase { * @brief This class packages the space packet causing the supervisor print the state of a GPIO * to the debug output. */ -class ReadGpio : public ploc::SpTcBase { +class ReadGpio : public TcBase { public: /** * @brief Constructor @@ -931,11 +1048,8 @@ class ReadGpio : public ploc::SpTcBase { * @param port * @param pin */ - ReadGpio(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_READ_GPIO); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + ReadGpio(TcParams params) + : TcBase(params, Apid::TMTC_MAN, static_cast(tc::TmtcId::READ_GPIO), 2) {} ReturnValue_t buildPacket(uint8_t port, uint8_t pin) { auto res = checkSizeAndSerializeHeader(); @@ -943,15 +1057,10 @@ class ReadGpio : public ploc::SpTcBase { return res; } initPacket(port, pin); - return calcCrc(); + return calcAndSetCrc(); } private: - static const uint16_t DATA_FIELD_LENGTH = 4; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - uint8_t port = 0; uint8_t pin = 0; @@ -961,65 +1070,10 @@ class ReadGpio : public ploc::SpTcBase { } }; -/** - * @brief This class packages the space packet to perform the factory reset. The op parameter is - * optional. - * - * @details: Without OP: All MRAM entries will be cleared. - * OP = 0x01: Only the mirror entries will be wiped. - * OP = 0x02: Only the circular entries will be wiped. - */ -class FactoryReset : public ploc::SpTcBase { +class SetShutdownTimeout : public TcBase { public: - enum class Op { CLEAR_ALL, MIRROR_ENTRIES, CIRCULAR_ENTRIES }; - - /** - * @brief Constructor - * - * @param op - */ - FactoryReset(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.creator.setApid(APID_FACTORY_RESET); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } - - ReturnValue_t buildPacket(Op op) { - auto res = checkSizeAndSerializeHeader(); - if (res != returnvalue::OK) { - return res; - } - initPacket(op); - return calcCrc(); - } - - private: - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - void initPacket(Op op) { - size_t packetDataLen = 2; - switch (op) { - case Op::MIRROR_ENTRIES: - payloadStart[0] = 1; - packetDataLen = 3; - break; - case Op::CIRCULAR_ENTRIES: - payloadStart[0] = 2; - packetDataLen = 3; - break; - default: - break; - } - spParams.setDataFieldLen(packetDataLen); - } -}; - -class SetShutdownTimeout : public ploc::SpTcBase { - public: - SetShutdownTimeout(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setPayloadLen(PAYLOAD_LEN); - spParams.creator.setApid(APID_SET_SHUTDOWN_TIMEOUT); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetShutdownTimeout(TcParams params) + : TcBase(params, Apid::BOOT_MAN, static_cast(tc::BootManId::SHUTDOWN_TIMEOUT), 4) {} ReturnValue_t buildPacket(uint32_t timeout) { auto res = checkSizeAndSerializeHeader(); @@ -1027,14 +1081,10 @@ class SetShutdownTimeout : public ploc::SpTcBase { return res; } initPacket(timeout); - return calcCrc(); + return calcAndSetCrc(); } private: - static const uint16_t PAYLOAD_LEN = 4; // uint32_t timeout - - uint32_t timeout = 0; - void initPacket(uint32_t timeout) { size_t serLen = 0; SerializeAdapter::serialize(&timeout, payloadStart, &serLen, sizeof(timeout), @@ -1045,7 +1095,7 @@ class SetShutdownTimeout : public ploc::SpTcBase { /** * @brief Command to request CRC over memory region of the supervisor. */ -class CheckMemory : public ploc::SpTcBase { +class CheckMemory : public TcBase { public: /** * @brief Constructor @@ -1054,11 +1104,8 @@ class CheckMemory : public ploc::SpTcBase { * @param startAddress Start address of CRC calculation * @param length Length in bytes of memory region */ - CheckMemory(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setPayloadLen(PAYLOAD_LENGTH); - spParams.creator.setApid(APID_CHECK_MEMORY); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + CheckMemory(TcParams params) + : TcBase(params, Apid::MEM_MAN, static_cast(tc::MemManId::CHECK), 10) {} ReturnValue_t buildPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { auto res = checkSizeAndSerializeHeader(); @@ -1066,16 +1113,11 @@ class CheckMemory : public ploc::SpTcBase { return res; } initPacket(memoryId, startAddress, length); - return calcCrc(); + return calcAndSetCrc(); } private: - static const uint16_t PAYLOAD_LENGTH = 10; // length without CRC field - - uint8_t memoryId = 0; uint8_t n = 1; - uint32_t startAddress = 0; - uint32_t length = 0; void initPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { uint8_t* data = payloadStart; @@ -1093,7 +1135,7 @@ class CheckMemory : public ploc::SpTcBase { /** * @brief This class packages the space packet transporting a part of an MPSoC update. */ -class WriteMemory : public ploc::SpTcBase { +class WriteMemory : public TcBase { public: /** * @brief Constructor @@ -1102,10 +1144,8 @@ class WriteMemory : public ploc::SpTcBase { * @param sequenceCount Sequence count (first update packet expects 1 as sequence count) * @param updateData Pointer to buffer containing update data */ - WriteMemory(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.creator.setApid(APID_WRITE_MEMORY); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + WriteMemory(TcParams params) + : TcBase(params, Apid::MEM_MAN, static_cast(tc::MemManId::WRITE), 1) {} ReturnValue_t buildPacket(ccsds::SequenceFlags seqFlags, uint16_t sequenceCount, uint8_t memoryId, uint32_t startAddress, uint16_t length, uint8_t* updateData) { @@ -1115,12 +1155,15 @@ class WriteMemory : public ploc::SpTcBase { } spParams.creator.setSeqFlags(seqFlags); spParams.creator.setSeqCount(sequenceCount); - initPacket(memoryId, startAddress, length, updateData); - auto res = checkSizeAndSerializeHeader(); + auto res = initPacket(memoryId, startAddress, length, updateData); if (res != returnvalue::OK) { return res; } - return calcCrc(); + res = checkSizeAndSerializeHeader(); + if (res != returnvalue::OK) { + return res; + } + return calcAndSetCrc(); } // Although the space packet has space left for 1010 bytes of data to supervisor can only process // update packets with a maximum of 512 bytes. @@ -1134,16 +1177,16 @@ class WriteMemory : public ploc::SpTcBase { uint8_t* updateData) { uint8_t* data = payloadStart; if (updateDataLen % 2 != 0) { - spParams.setPayloadLen(META_DATA_LENGTH + updateDataLen + 1); + setLenFromPayloadLen(META_DATA_LENGTH + updateDataLen + 1); } else { - spParams.setPayloadLen(META_DATA_LENGTH + updateDataLen); + setLenFromPayloadLen(META_DATA_LENGTH + updateDataLen); } // To avoid crashes in this unexpected case ReturnValue_t result = checkPayloadLen(); if (result != returnvalue::OK) { return result; } - size_t serializedSize = 6; + size_t serializedSize = MIN_TMTC_LEN; SerializeAdapter::serialize(&memoryId, &data, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); SerializeAdapter::serialize(&n, &data, &serializedSize, spParams.maxSize, @@ -1156,22 +1199,69 @@ class WriteMemory : public ploc::SpTcBase { if (updateDataLen % 2 != 0) { // The data field must be two bytes aligned. Thus, in case the number of bytes to write is odd // a value of zero is added here - data[updateDataLen + 1] = 0; + data[updateDataLen] = 0; } return returnvalue::OK; } }; +/** + * @brief This class packages the space packet to wipe or dump parts of the MRAM. + */ +class MramCmd : public TcBase { + public: + enum class MramAction { WIPE, DUMP }; + + /** + * @brief Constructor + * + * @param start Start address of the MRAM section to wipe or dump + * @param stop End address of the MRAM section to wipe or dump + * @param action Dump or wipe MRAM + * + * @note The content at the stop address is excluded from the dump or wipe operation. + */ + MramCmd(TcParams params) : TcBase(params, Apid::DATA_LOGGER) { setLenFromPayloadLen(6); } + + ReturnValue_t buildPacket(uint32_t start, uint32_t stop, MramAction action) { + if (action == MramAction::WIPE) { + setServiceId(static_cast(tc::DataLoggerServiceId::WIPE_MRAM)); + } else if (action == MramAction::DUMP) { + setServiceId(static_cast(tc::DataLoggerServiceId::DUMP_MRAM)); + } else { + sif::debug << "WipeMram: Invalid action specified"; + } + auto res = checkSizeAndSerializeHeader(); + if (res != returnvalue::OK) { + return res; + } + initPacket(start, stop); + return calcAndSetCrc(); + } + + private: + uint32_t start = 0; + uint32_t stop = 0; + + void initPacket(uint32_t start, uint32_t stop) { + uint8_t concatBuffer[6]; + concatBuffer[0] = static_cast(start >> 16); + concatBuffer[1] = static_cast(start >> 8); + concatBuffer[2] = static_cast(start); + concatBuffer[3] = static_cast(stop >> 16); + concatBuffer[4] = static_cast(stop >> 8); + concatBuffer[5] = static_cast(stop); + std::memcpy(payloadStart, concatBuffer, sizeof(concatBuffer)); + } +}; + /** * @brief This class can be used to package erase memory command */ -class EraseMemory : public ploc::SpTcBase { +class EraseMemory : public TcBase { public: - EraseMemory(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setPayloadLen(PAYLOAD_LENGTH); - spParams.creator.setApid(APID_ERASE_MEMORY); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + EraseMemory(TcParams params) + : TcBase(params, Apid::MEM_MAN, static_cast(tc::MemManId::ERASE), PAYLOAD_LENGTH) {} ReturnValue_t buildPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { auto res = checkSizeAndSerializeHeader(); @@ -1179,16 +1269,13 @@ class EraseMemory : public ploc::SpTcBase { return res; } initPacket(memoryId, startAddress, length); - return calcCrc(); + return calcAndSetCrc(); } private: static const uint16_t PAYLOAD_LENGTH = 10; // length without CRC field - uint8_t memoryId = 0; uint8_t n = 1; - uint32_t startAddress = 0; - uint32_t length = 0; void initPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { uint8_t* data = payloadStart; @@ -1204,486 +1291,440 @@ class EraseMemory : public ploc::SpTcBase { } }; -/** - * @brief This class creates the space packet to enable the auto TM generation - */ -class EnableAutoTm : public ploc::SpTcBase { +class VerificationReport { public: - EnableAutoTm(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setPayloadLen(PAYLOAD_LENGTH); - spParams.creator.setApid(APID_AUTO_TM); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + VerificationReport(TmBase& readerBase) : readerBase(readerBase) {} - ReturnValue_t buildPacket() { - auto res = checkSizeAndSerializeHeader(); - if (res != returnvalue::OK) { - return res; + virtual ~VerificationReport() = default; + + virtual ReturnValue_t parse() { + if (not readerBase.crcIsOk()) { + return result::CRC_FAILURE; } - payloadStart[0] = ENABLE; - return calcCrc(); - } - - private: - static const uint16_t PAYLOAD_LENGTH = 1; // length without CRC field - static const uint8_t ENABLE = 1; -}; - -/** - * @brief This class creates the space packet to disable the auto TM generation - */ -class DisableAutoTm : public ploc::SpTcBase { - public: - DisableAutoTm(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setPayloadLen(PAYLOAD_LENGTH); - spParams.creator.setApid(APID_AUTO_TM); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } - - ReturnValue_t buildPacket() { - auto res = checkSizeAndSerializeHeader(); - if (res != returnvalue::OK) { - return res; + if (readerBase.getModuleApid() != Apid::TMTC_MAN) { + return result::INVALID_APID; } - payloadStart[0] = DISABLE; - return calcCrc(); - } - - private: - static const uint16_t PAYLOAD_LENGTH = 1; // length without CRC field - static const uint8_t DISABLE = 0; -}; - -/** - * @brief This class creates the space packet to request the logging data from the supervisor - */ -class RequestLoggingData : public ploc::SpTcBase { - public: - /** - * Subapid - */ - enum class Sa : uint8_t { - REQUEST_COUNTERS = 1, /**< REQUEST_COUNTERS */ - REQUEST_EVENT_BUFFERS = 2, /**< REQUEST_EVENT_BUFFERS */ - CLEAR_COUNTERS = 3, /**< CLEAR_COUNTERS */ - SET_LOGGING_TOPIC = 4 /**< SET_LOGGING_TOPIC */ - }; - - RequestLoggingData(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setPayloadLen(PAYLOAD_LENGTH); - spParams.creator.setApid(APID_REQUEST_LOGGING_DATA); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } - - /** - * @param sa - * @param tpc Topic - * @return - */ - ReturnValue_t buildPacket(Sa sa, uint8_t tpc = 0) { - auto res = checkSizeAndSerializeHeader(); - if (res != returnvalue::OK) { - return res; + if (readerBase.getBufSize() < MIN_TMTC_LEN + PAYLOAD_LEN or + readerBase.getPayloadLen() < PAYLOAD_LEN) { + sif::error << "VerificationReport: Invalid verification report, payload too small" + << std::endl; + return result::BUF_TOO_SMALL; } - payloadStart[0] = static_cast(sa); - payloadStart[1] = tpc; - return calcCrc(); + const uint8_t* payloadStart = readerBase.getPayloadStart(); + size_t remLen = PAYLOAD_LEN; + ReturnValue_t result = SerializeAdapter::deSerialize(&refApid, &payloadStart, &remLen, + SerializeIF::Endianness::BIG); + if (result != returnvalue::OK) { + sif::debug << "VerificationReport: Failed to deserialize reference APID field" << std::endl; + return result; + } + result = SerializeAdapter::deSerialize(&refServiceId, &payloadStart, &remLen, + SerializeIF::Endianness::BIG); + if (result != returnvalue::OK) { + sif::debug << "VerificationReport: Failed to deserialize reference Service ID field" + << std::endl; + return result; + } + result = SerializeAdapter::deSerialize(&refSeqCount, &payloadStart, &remLen, + SerializeIF::Endianness::BIG); + if (result != returnvalue::OK) { + sif::debug << "VerificationReport: Failed to deserialize reference sequence count field" + << std::endl; + return result; + } + result = SerializeAdapter::deSerialize(&statusCode, &payloadStart, &remLen, + SerializeIF::Endianness::BIG); + if (result != returnvalue::OK) { + sif::debug << "VerificationReport: Failed to deserialize status code field" << std::endl; + return result; + } + return returnvalue::OK; } - private: - static const uint16_t PAYLOAD_LENGTH = 2; // length without CRC field - static const uint8_t TPC_OFFSET = 1; -}; - -class VerificationReport : public ploc::SpTmReader { - public: - VerificationReport(const uint8_t* buf, size_t maxSize) : ploc::SpTmReader(buf, maxSize) {} - /** * @brief Gets the APID of command which caused the transmission of this verification report. */ - uint16_t getRefApid() { - uint16_t refApid = 0; - size_t size = 0; - const uint8_t* refApidPtr = this->getPacketData(); - ReturnValue_t result = - SerializeAdapter::deSerialize(&refApid, refApidPtr, &size, SerializeIF::Endianness::BIG); - if (result != returnvalue::OK) { - sif::debug << "ExecutionReport: Failed to deserialize reference APID field" << std::endl; - return result; + uint8_t getRefModuleApid() const { return refApid; } + + uint8_t getRefServiceId() const { return refServiceId; } + + uint16_t getRefSequenceCount() const { return refSeqCount; } + + uint32_t getStatusCode() const { return statusCode; } + + virtual void printStatusInformation(const char* prefix) { + bool codeHandled = true; + if (statusCode < 0x100) { + GeneralStatusCode code = static_cast(getStatusCode()); + switch (code) { + case GeneralStatusCode::OK: { + sif::warning << prefix << "Ok" << std::endl; + break; + } + case GeneralStatusCode::INIT_ERROR: { + sif::warning << prefix << "Init error" << std::endl; + break; + } + case GeneralStatusCode::BAD_PARAM: { + sif::warning << prefix << "Bad param" << std::endl; + break; + } + case GeneralStatusCode::NOT_INITIALIZED: { + sif::warning << prefix << "Not initialized" << std::endl; + break; + } + case GeneralStatusCode::BAD_PERIPH_ID: { + sif::warning << prefix << "Bad periph ID" << std::endl; + break; + } + case GeneralStatusCode::TIMEOUT: { + sif::warning << prefix << "Timeout" << std::endl; + break; + } + case GeneralStatusCode::RX_ERROR: { + sif::warning << prefix << "RX error" << std::endl; + break; + } + case GeneralStatusCode::TX_ERROR: { + sif::warning << prefix << "TX error" << std::endl; + break; + } + case GeneralStatusCode::BUF_EMPTY: { + sif::warning << prefix << "Buf empty" << std::endl; + break; + } + case GeneralStatusCode::NAK: { + sif::warning << prefix << "Nak, default error code" << std::endl; + break; + } + case GeneralStatusCode::ARB_LOST: { + sif::warning << prefix << "Arb lost" << std::endl; + break; + } + case GeneralStatusCode::BUSY: { + sif::warning << prefix << "Busy" << std::endl; + break; + } + case GeneralStatusCode::NOT_IMPL: { + sif::warning << prefix << "Not implemented" << std::endl; + break; + } + case GeneralStatusCode::ALIGNMENT_ERROR: { + sif::warning << prefix << "Alignment error" << std::endl; + break; + } + case GeneralStatusCode::PERIPH_ERROR: { + sif::warning << prefix << "Periph error" << std::endl; + break; + } + case GeneralStatusCode::FAILED_LATCH: { + sif::warning << prefix << "Failed latch" << std::endl; + break; + } + case GeneralStatusCode::GPIO_HIGH: { + sif::warning << prefix << "GPIO high" << std::endl; + break; + } + case GeneralStatusCode::GPIO_LOW: { + sif::warning << prefix << "GPIO low" << std::endl; + break; + } + case GeneralStatusCode::TEST_PASSED: { + sif::warning << prefix << "Test passed" << std::endl; + break; + } + case GeneralStatusCode::TEST_FAILED: { + sif::warning << prefix << "Test failed" << std::endl; + break; + } + default: { + codeHandled = false; + break; + } + } + } else if (statusCode < 0x200 and statusCode >= 0x100) { + BootManStatusCode code = static_cast(statusCode); + switch (code) { + case BootManStatusCode::NOTHING_TODO: { + sif::warning << prefix << "Nothing to do" << std::endl; + break; + } + case BootManStatusCode::POWER_FAULT: { + sif::warning << prefix << "Power fault" << std::endl; + break; + } + case BootManStatusCode::INVALID_LENGTH: { + sif::warning << prefix << "Invalid length" << std::endl; + break; + } + case BootManStatusCode::OUT_OF_RANGE: { + sif::warning << prefix << "Out of range, lenght check of parameter failed" << std::endl; + break; + } + case BootManStatusCode::OUT_OF_HEAP_MEMORY: { + sif::warning << prefix << "Out of heap memory" << std::endl; + break; + } + case BootManStatusCode::INVALID_STATE_TRANSITION: { + sif::warning << prefix << "Invalid state transition" << std::endl; + break; + } + case BootManStatusCode::MPSOC_ALREADY_BOOTING: { + sif::warning << prefix << "MPSoC already booting" << std::endl; + break; + } + case BootManStatusCode::MPSOC_ALREADY_OPERATIONAL: { + sif::warning << prefix << "MPSoC already operational" << std::endl; + break; + } + case BootManStatusCode::MPSOC_BOOT_FAILED: { + sif::warning << prefix << "MPSoC boot failed" << std::endl; + break; + } + default: { + codeHandled = false; + break; + } + } + } else if (statusCode < 0x300 and statusCode >= 0x200) { + MemManStatusCode code = static_cast(statusCode); + switch (code) { + case MemManStatusCode::SP_NOT_AVAILABLE: { + sif::warning << prefix << "SP not available" << std::endl; + break; + } + case MemManStatusCode::SP_DATA_INSUFFICIENT: { + sif::warning << prefix << "SP data insufficient" << std::endl; + break; + } + case MemManStatusCode::SP_MEMORY_ID_INVALID: { + sif::warning << prefix << "SP data insufficient" << std::endl; + break; + } + case MemManStatusCode::MPSOC_NOT_IN_RESET: { + sif::warning << prefix << "MPSoC not in reset" << std::endl; + break; + } + case MemManStatusCode::FLASH_INIT_FAILED: { + sif::warning << prefix << "Flash init failed" << std::endl; + break; + } + case MemManStatusCode::FLASH_ERASE_FAILED: { + sif::warning << prefix << "Flash erase failed" << std::endl; + break; + } + case MemManStatusCode::FLASH_WRITE_FAILED: { + sif::warning << prefix << "Flash write failed" << std::endl; + break; + } + case MemManStatusCode::FLASH_VERIFY_FAILED: { + sif::warning << prefix << "Flash verify failed" << std::endl; + break; + } + case MemManStatusCode::CANNOT_ACCESS_TM: { + sif::warning << prefix << "Can not access tm" << std::endl; + break; + } + case MemManStatusCode::CANNOT_SEND_TM: { + sif::warning << prefix << "Can not access tm" << std::endl; + break; + } + default: { + codeHandled = false; + break; + } + } + } else if (statusCode < 0x400 and statusCode >= 0x300) { + PowerManStatusCode code = static_cast(statusCode); + switch (code) { + case PowerManStatusCode::PG_LOW: { + sif::warning << prefix << "PG low" << std::endl; + break; + } + case PowerManStatusCode::PG_5V_LOW: { + sif::warning << prefix << "PG 5V low" << std::endl; + break; + } + case PowerManStatusCode::PG_0V85_LOW: { + sif::warning << prefix << "PG 0V85 low" << std::endl; + break; + } + case PowerManStatusCode::PG_1V8_LOW: { + sif::warning << prefix << "PG 1V8 low" << std::endl; + break; + } + case PowerManStatusCode::PG_MISC_LOW: { + sif::warning << prefix << "PG misc low" << std::endl; + break; + } + case PowerManStatusCode::PG_3V3_LOW: { + sif::warning << prefix << "PG 3V3 low" << std::endl; + break; + } + case PowerManStatusCode::PG_MB_VAIO_LOW: { + sif::warning << prefix << "PG mb vaio low" << std::endl; + break; + } + case PowerManStatusCode::PG_MB_MPSOCIO_LOW: { + sif::warning << prefix << "PG mb mpsocio low" << std::endl; + break; + } + default: { + codeHandled = false; + break; + } + } + } else if (statusCode >= 0x600) { + TmtcManStatusCode code = static_cast(statusCode); + switch (code) { + case TmtcManStatusCode::BUF_FULL: { + sif::warning << prefix << "TMTC MAN: Buffer full" << std::endl; + break; + } + case TmtcManStatusCode::WRONG_APID: { + sif::warning << prefix << "TMTC MAN: Wrong APID" << std::endl; + break; + } + case TmtcManStatusCode::WRONG_SERVICE_ID: { + sif::warning << prefix << "TMTC MAN: Wrong Service ID" << std::endl; + break; + } + case TmtcManStatusCode::TC_DELIVERY_ACCEPTED: { + sif::warning << prefix << "TMTC MAN: TC accepted" << std::endl; + break; + } + case TmtcManStatusCode::TC_DELIVERY_REJECTED: { + sif::warning << prefix << "TMTC MAN: TC rejected" << std::endl; + break; + } + case TmtcManStatusCode::TC_PACKET_LEN_INCORRECT: { + sif::warning << prefix << "TMTC MAN: TC packet lenght incorrect" << std::endl; + break; + } + case TmtcManStatusCode::BAD_CRC: { + sif::warning << prefix << "TMTC MAN: Bad CRC" << std::endl; + break; + } + case TmtcManStatusCode::BAD_DEST: { + sif::warning << prefix << "TMTC MAN: Bad destination" << std::endl; + break; + } + case TmtcManStatusCode::BAD_SP_HEADER: { + sif::warning << prefix << "TMTC MAN: Bad SP header" << std::endl; + break; + } + default: { + codeHandled = false; + break; + } + } + } + if (not codeHandled) { + sif::warning << prefix << "Invalid or unimplemented status code: 0x" << std::hex + << std::setfill('0') << std::setw(4) << static_cast(statusCode) + << std::dec << std::endl; } - return refApid; } - uint16_t getStatusCode() { - uint16_t statusCode = 0; - size_t size = 0; - const uint8_t* statusCodePtr = this->getPacketData() + OFFSET_STATUS_CODE; - ReturnValue_t result = SerializeAdapter::deSerialize(&statusCode, statusCodePtr, &size, - SerializeIF::Endianness::BIG); - if (result != returnvalue::OK) { - sif::debug << "ExecutionReport: Failed to deserialize status code field" << std::endl; - return result; - } - return statusCode; - } - - virtual ReturnValue_t checkApid() { return returnvalue::FAILED; } - - private: - static const uint8_t OFFSET_STATUS_CODE = 4; + protected: + TmBase& readerBase; + uint8_t refApid = 0; + uint8_t refServiceId = 0; + uint16_t refSeqCount = 0; + uint32_t statusCode = 0; + static const size_t PAYLOAD_LEN = 8; }; class AcknowledgmentReport : public VerificationReport { public: - AcknowledgmentReport(const uint8_t* buf, size_t maxSize) : VerificationReport(buf, maxSize) {} + AcknowledgmentReport(TmBase& readerBase) : VerificationReport(readerBase) {} - ReturnValue_t checkApid() { - uint16_t apid = this->getApid(); - if (apid == APID_ACK_SUCCESS) { - return returnvalue::OK; - } else if (apid == APID_ACK_FAILURE) { - printStatusInformation(); - return SupvReturnValuesIF::RECEIVED_ACK_FAILURE; - } else { - sif::warning << "AcknowledgmentReport::checkApid: Invalid apid: 0x" << std::hex << apid - << std::endl; - return SupvReturnValuesIF::INVALID_APID; + virtual ReturnValue_t parse() override { + if (readerBase.getServiceId() != static_cast(tm::TmtcId::ACK) and + readerBase.getServiceId() != static_cast(tm::TmtcId::NAK)) { + return result::INVALID_SERVICE_ID; } + return VerificationReport::parse(); } void printStatusInformation() { - StatusCode statusCode = static_cast(getStatusCode()); - const char* prefix = "Supervisor acknowledgment report status: "; - switch (statusCode) { - case StatusCode::OK: { - sif::warning << prefix << "Ok" << std::endl; - break; - } - case StatusCode::BAD_PARAM: { - sif::warning << prefix << "Bad param" << std::endl; - break; - } - case StatusCode::TIMEOUT: { - sif::warning << prefix << "Timeout" << std::endl; - break; - } - case StatusCode::RX_ERROR: { - sif::warning << prefix << "RX error" << std::endl; - break; - } - case StatusCode::TX_ERROR: { - sif::warning << prefix << "TX error" << std::endl; - break; - } - case StatusCode::HEADER_EMPTY: { - sif::warning << prefix << "Header empty" << std::endl; - break; - } - case StatusCode::DEFAULT_NAK: { - sif::warning << prefix << "Default code for NAK" << std::endl; - break; - } - case StatusCode::ROUTE_PACKET: { - sif::warning << prefix << "Route packet error" << std::endl; - break; - } - default: - sif::warning << "AcknowledgmentReport::printStatusInformation: Invalid status code: 0x" - << std::hex << static_cast(statusCode) << std::endl; - break; - } + VerificationReport::printStatusInformation(STATUS_PRINTOUT_PREFIX); } private: - enum class StatusCode : uint16_t { - OK = 0x0, - BAD_PARAM = 0x1, - TIMEOUT = 0x2, - RX_ERROR = 0x3, - TX_ERROR = 0x4, - HEADER_EMPTY = 0x5, - DEFAULT_NAK = 0x6, - ROUTE_PACKET = 0x7 - }; + static constexpr char STATUS_PRINTOUT_PREFIX[] = "SUPV NAK Status: "; }; class ExecutionReport : public VerificationReport { public: - ExecutionReport(const uint8_t* buf, size_t maxSize) : VerificationReport(buf, maxSize) {} + ExecutionReport(TmBase& readerBase) : VerificationReport(readerBase) {} - ReturnValue_t checkApid() { - uint16_t apid = this->getApid(); - if (apid == APID_EXE_SUCCESS) { - return returnvalue::OK; - } else if (apid == APID_EXE_FAILURE) { - printStatusInformation(); - return SupvReturnValuesIF::RECEIVED_EXE_FAILURE; - } else { - sif::warning << "ExecutionReport::checkApid: Invalid apid: 0x" << std::hex << apid - << std::endl; - return SupvReturnValuesIF::INVALID_APID; + TmBase& getReader() { return readerBase; } + + ReturnValue_t parse() override { + if (readerBase.getServiceId() != static_cast(tm::TmtcId::EXEC_ACK) and + readerBase.getServiceId() != static_cast(tm::TmtcId::EXEC_NAK)) { + return returnvalue::FAILED; } + return VerificationReport::parse(); + } + + void printStatusInformation() { + VerificationReport::printStatusInformation(STATUS_PRINTOUT_PREFIX); } private: - static constexpr char STATUS_PRINTOUT_PREFIX[] = "Supervisor execution failure report status: "; + static constexpr char STATUS_PRINTOUT_PREFIX[] = "SUPV EXE NAK Status: "; +}; - enum class StatusCode : uint16_t { - OK = 0x0, - INIT_ERROR = 0x1, - BAD_PARAM = 0x2, - NOT_INITIALIZED = 0x3, - BAD_PERIPH_ID = 0x4, - TIMEOUT = 0x5, - RX_ERROR = 0x6, - TX_ERROR = 0x7, - BUF_EMPTY = 0x8, - BUF_FULL = 0x9, - NAK = 0xA, - ARB_LOST = 0xB, - BUSY = 0xC, - NOT_IMPLEMENTED = 0xD, - ALIGNEMENT_ERROR = 0xE, - PERIPH_ERR = 0xF, - FAILED_LATCH = 0x10, - GPIO_HIGH = 0x11, - GPIO_LOW = 0x12, - TEST_PASSED = 0x13, - TEST_FAILED = 0x14, - NOTHING_TODO = 0x100, - POWER_FAULT = 0x101, - INVALID_LENGTH = 0x102, - OUT_OF_RANGE = 0x103, - OUT_OF_HEAP_MEMORY = 0x104, - INVALID_STATE_TRANSITION = 0x105, - MPSOC_ALREADY_BOOTING = 0x106, - MPSOC_ALREADY_OPERATIONAL = 0x107, - MPSOC_BOOT_FAILED = 0x108, - SP_NOT_AVAILABLE = 0x200, - SP_DATA_INSUFFICIENT = 0x201, - SP_MEMORY_ID_INVALID = 0x202, - MPSOC_NOT_IN_RESET = 0x203, - FLASH_INIT_FAILED = 0x204, - FLASH_ERASE_FAILED = 0x205, - FLASH_WRITE_FAILED = 0x206, - FLASH_VERIFY_FAILED = 0x207, - CANNOT_ACCESS_TM = 0x208, - CANNOT_SEND_TM = 0x209, - PG_LOW = 0x300, - PG_5V_LOW = 0x301, - PG_0V85_LOW = 0x302, - PG_1V8_LOW = 0x303, - PG_MISC_LOW = 0x304, - PG_3V3_LOW = 0x305, - PG_MB_VAIO_LOW = 0x306, - PG_MB_MPSOCIO_LOW = 0x307 - }; +class UpdateStatusReport { + public: + UpdateStatusReport(TmBase& tmReader) : tmReader(tmReader) {} - void printStatusInformation() { - StatusCode statusCode = static_cast(getStatusCode()); - switch (statusCode) { - case StatusCode::OK: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Ok" << std::endl; - break; - } - case StatusCode::INIT_ERROR: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Init error" << std::endl; - break; - } - case StatusCode::BAD_PARAM: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Bad param" << std::endl; - break; - } - case StatusCode::NOT_INITIALIZED: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Not initialized" << std::endl; - break; - } - case StatusCode::BAD_PERIPH_ID: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Bad periph ID" << std::endl; - break; - } - case StatusCode::TIMEOUT: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Timeout" << std::endl; - break; - } - case StatusCode::RX_ERROR: { - sif::warning << STATUS_PRINTOUT_PREFIX << "RX error" << std::endl; - break; - } - case StatusCode::TX_ERROR: { - sif::warning << STATUS_PRINTOUT_PREFIX << "TX error" << std::endl; - break; - } - case StatusCode::BUF_EMPTY: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Buf empty" << std::endl; - break; - } - case StatusCode::BUF_FULL: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Buf full" << std::endl; - break; - } - case StatusCode::NAK: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Nak, default error code" << std::endl; - break; - } - case StatusCode::ARB_LOST: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Arb lost" << std::endl; - break; - } - case StatusCode::BUSY: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Busy" << std::endl; - break; - } - case StatusCode::NOT_IMPLEMENTED: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Not implemented" << std::endl; - break; - } - case StatusCode::ALIGNEMENT_ERROR: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Alignment error" << std::endl; - break; - } - case StatusCode::PERIPH_ERR: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Periph error" << std::endl; - break; - } - case StatusCode::FAILED_LATCH: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Failed latch" << std::endl; - break; - } - case StatusCode::GPIO_HIGH: { - sif::warning << STATUS_PRINTOUT_PREFIX << "GPIO high" << std::endl; - break; - } - case StatusCode::GPIO_LOW: { - sif::warning << STATUS_PRINTOUT_PREFIX << "GPIO low" << std::endl; - break; - } - case StatusCode::TEST_PASSED: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Test passed" << std::endl; - break; - } - case StatusCode::TEST_FAILED: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Test failed" << std::endl; - break; - } - case StatusCode::NOTHING_TODO: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Nothing todo, not an error but a warning" - << std::endl; - break; - } - case StatusCode::POWER_FAULT: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Power fault" << std::endl; - break; - } - case StatusCode::INVALID_LENGTH: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Invalid length" << std::endl; - break; - } - case StatusCode::OUT_OF_RANGE: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Out of range, lenght check of parameter failed" - << std::endl; - break; - } - case StatusCode::OUT_OF_HEAP_MEMORY: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Out of heap memory" << std::endl; - break; - } - case StatusCode::INVALID_STATE_TRANSITION: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Invalid state transition" << std::endl; - break; - } - case StatusCode::MPSOC_ALREADY_BOOTING: { - sif::warning << STATUS_PRINTOUT_PREFIX << "MPSoC already booting" << std::endl; - break; - } - case StatusCode::MPSOC_ALREADY_OPERATIONAL: { - sif::warning << STATUS_PRINTOUT_PREFIX << "MPSoC already operational" << std::endl; - break; - } - case StatusCode::MPSOC_BOOT_FAILED: { - sif::warning << STATUS_PRINTOUT_PREFIX << "MPSoC boot failed" << std::endl; - break; - } - case StatusCode::SP_NOT_AVAILABLE: { - sif::warning << STATUS_PRINTOUT_PREFIX << "SP not available" << std::endl; - break; - } - case StatusCode::SP_DATA_INSUFFICIENT: { - sif::warning << STATUS_PRINTOUT_PREFIX << "SP data insufficient" << std::endl; - break; - } - case StatusCode::SP_MEMORY_ID_INVALID: { - sif::warning << STATUS_PRINTOUT_PREFIX << "SP data insufficient" << std::endl; - break; - } - case StatusCode::MPSOC_NOT_IN_RESET: { - sif::warning << STATUS_PRINTOUT_PREFIX << "MPSoC not in reset" << std::endl; - break; - } - case StatusCode::FLASH_INIT_FAILED: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Flash init failed" << std::endl; - break; - } - case StatusCode::FLASH_ERASE_FAILED: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Flash erase failed" << std::endl; - break; - } - case StatusCode::FLASH_WRITE_FAILED: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Flash write failed" << std::endl; - break; - } - case StatusCode::FLASH_VERIFY_FAILED: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Flash verify failed" << std::endl; - break; - } - case StatusCode::CANNOT_ACCESS_TM: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Can not access tm" << std::endl; - break; - } - case StatusCode::CANNOT_SEND_TM: { - sif::warning << STATUS_PRINTOUT_PREFIX << "Can not access tm" << std::endl; - break; - } - case StatusCode::PG_LOW: { - sif::warning << STATUS_PRINTOUT_PREFIX << "PG low" << std::endl; - break; - } - case StatusCode::PG_5V_LOW: { - sif::warning << STATUS_PRINTOUT_PREFIX << "PG 5V low" << std::endl; - break; - } - case StatusCode::PG_0V85_LOW: { - sif::warning << STATUS_PRINTOUT_PREFIX << "PG 0V85 low" << std::endl; - break; - } - case StatusCode::PG_1V8_LOW: { - sif::warning << STATUS_PRINTOUT_PREFIX << "PG 1V8 low" << std::endl; - break; - } - case StatusCode::PG_MISC_LOW: { - sif::warning << STATUS_PRINTOUT_PREFIX << "PG misc low" << std::endl; - break; - } - case StatusCode::PG_3V3_LOW: { - sif::warning << STATUS_PRINTOUT_PREFIX << "PG 3V3 low" << std::endl; - break; - } - case StatusCode::PG_MB_VAIO_LOW: { - sif::warning << STATUS_PRINTOUT_PREFIX << "PG mb vaio low" << std::endl; - break; - } - case StatusCode::PG_MB_MPSOCIO_LOW: { - sif::warning << STATUS_PRINTOUT_PREFIX << "PG mb mpsocio low" << std::endl; - break; - } - default: - sif::warning << "ExecutionReport::printStatusInformation: Invalid status code: 0x" - << std::hex << std::setfill('0') << std::setw(4) - << static_cast(statusCode) << std::dec << std::endl; - break; + ReturnValue_t parse() { + if (not tmReader.crcIsOk()) { + return result::CRC_FAILURE; } + if (tmReader.getModuleApid() != Apid::MEM_MAN) { + return result::INVALID_APID; + } + if (tmReader.getBufSize() < MIN_TMTC_LEN + PAYLOAD_LEN or + tmReader.getPayloadLen() < PAYLOAD_LEN) { + sif::error << "VerificationReport: Invalid verification report, payload too small" + << std::endl; + return result::BUF_TOO_SMALL; + } + size_t remLen = tmReader.getPayloadLen(); + const uint8_t* dataFieldPtr = tmReader.getPayloadStart(); + SerializeAdapter::deSerialize(&memoryId, &dataFieldPtr, &remLen, SerializeIF::Endianness::BIG); + SerializeAdapter::deSerialize(&n, &dataFieldPtr, &remLen, SerializeIF::Endianness::BIG); + SerializeAdapter::deSerialize(&startAddress, &dataFieldPtr, &remLen, + SerializeIF::Endianness::BIG); + SerializeAdapter::deSerialize(&length, &dataFieldPtr, &remLen, SerializeIF::Endianness::BIG); + SerializeAdapter::deSerialize(&crc, &dataFieldPtr, &remLen, SerializeIF::Endianness::BIG); + return returnvalue::OK; } + + ReturnValue_t verifyCrc(uint16_t goodCrc) const { + if (crc != goodCrc) { + return result::UPDATE_CRC_FAILURE; + } + return returnvalue::OK; + } + + uint16_t getCrc() const { return crc; } + + private: + TmBase& tmReader; + + // Nominal size of the space packet + static const uint16_t PAYLOAD_LEN = 12; // header, data field and crc + + uint8_t memoryId = 0; + uint8_t n = 0; + uint32_t startAddress = 0; + uint32_t length = 0; + uint16_t crc = 0; }; /** @@ -1840,56 +1881,6 @@ class LoggingReport : public StaticLocalDataSet { } }; -class UpdateStatusReport : public ploc::SpTmReader { - public: - UpdateStatusReport() = default; - UpdateStatusReport(const uint8_t* buf, size_t maxSize) : ploc::SpTmReader(buf, maxSize) {} - - ReturnValue_t parseDataField() { - ReturnValue_t result = lengthCheck(); - if (result != returnvalue::OK) { - return result; - } - const uint8_t* dataFieldPtr = getFullData() + ccsds::HEADER_LEN; - size_t size = 12; - SerializeAdapter::deSerialize(&memoryId, &dataFieldPtr, &size, SerializeIF::Endianness::BIG); - SerializeAdapter::deSerialize(&n, &dataFieldPtr, &size, SerializeIF::Endianness::BIG); - SerializeAdapter::deSerialize(&startAddress, &dataFieldPtr, &size, - SerializeIF::Endianness::BIG); - SerializeAdapter::deSerialize(&length, &dataFieldPtr, &size, SerializeIF::Endianness::BIG); - SerializeAdapter::deSerialize(&crc, &dataFieldPtr, &size, SerializeIF::Endianness::BIG); - return returnvalue::OK; - } - - ReturnValue_t verifycrc(uint16_t goodCrc) const { - if (crc != goodCrc) { - return SupvReturnValuesIF::UPDATE_CRC_FAILURE; - } - return returnvalue::OK; - } - - uint16_t getCrc() const { return crc; } - - uint16_t getNominalSize() const { return FULL_SIZE; } - - private: - // Nominal size of the space packet - static const uint16_t FULL_SIZE = 20; // header, data field and crc - - uint8_t memoryId = 0; - uint8_t n = 0; - uint32_t startAddress = 0; - uint32_t length = 0; - uint16_t crc = 0; - - ReturnValue_t lengthCheck() { - if (getFullPacketLen() != FULL_SIZE) { - return SupvReturnValuesIF::UPDATE_STATUS_REPORT_INVALID_LENGTH; - } - return returnvalue::OK; - } -}; - /** * @brief This dataset stores the ADC report. */ @@ -1969,6 +1960,197 @@ class AdcReport : public StaticLocalDataSet { sif::info << "AdcReport: ADC eng 15: " << this->adcEng15 << std::endl; } }; + +namespace notimpl { + +/** + * @brief This class packages the space packet to perform the factory reset. The op parameter is + * optional. + * + * @details: Without OP: All MRAM entries will be cleared. + * OP = 0x01: Only the mirror entries will be wiped. + * OP = 0x02: Only the circular entries will be wiped. + */ +class FactoryReset : public TcBase { + public: + enum class Op { CLEAR_ALL, MIRROR_ENTRIES, CIRCULAR_ENTRIES }; + + /** + * @brief Constructor + * + * @param op + */ + FactoryReset(TcParams params) : TcBase(params, Apid::TMTC_MAN, 0x11, 1) {} + + ReturnValue_t buildPacket(Op op) { + auto res = checkSizeAndSerializeHeader(); + if (res != returnvalue::OK) { + return res; + } + initPacket(op); + return calcAndSetCrc(); + } + + private: + void initPacket(Op op) { + size_t packetDataLen = 2; + switch (op) { + case Op::MIRROR_ENTRIES: + payloadStart[0] = 1; + packetDataLen = 3; + break; + case Op::CIRCULAR_ENTRIES: + payloadStart[0] = 2; + packetDataLen = 3; + break; + default: + break; + } + spParams.setFullPayloadLen(packetDataLen); + } +}; + +/** + * @brief This class creates the command to enable or disable the NVMs connected to the + * supervisor. + */ +class EnableNvms : public TcBase { + public: + /** + * @brief Constructor + * + * @param mem The memory to boot from: NVM0 (0), NVM1 (1) + * @param bp0 Partition pin 0 + * @param bp1 Partition pin 1 + * @param bp2 Partition pin 2 + */ + EnableNvms(TcParams params) : TcBase(params, Apid::TMTC_MAN, 0x06, 2) {} + + ReturnValue_t buildPacket(uint8_t nvm01, uint8_t nvm3) { + auto res = checkSizeAndSerializeHeader(); + if (res != returnvalue::OK) { + return res; + } + initPacket(nvm01, nvm3); + return calcAndSetCrc(); + } + + private: + void initPacket(uint8_t nvm01, uint8_t nvm3) { + payloadStart[0] = nvm01; + payloadStart[1] = nvm3; + } +}; + +/** + * @brief This class creates the space packet to enable the auto TM generation + */ +class EnableAutoTm : public TcBase { + public: + EnableAutoTm(TcParams params) : TcBase(params) { + spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); + // spParams.creator.setApid(APID_AUTO_TM); + // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket() { + auto res = checkSizeAndSerializeHeader(); + if (res != returnvalue::OK) { + return res; + } + payloadStart[0] = ENABLE; + return calcAndSetCrc(); + } + + private: + static const uint16_t PAYLOAD_LENGTH = 1; // length without CRC field + static const uint8_t ENABLE = 1; +}; + +/** + * @brief This class creates the space packet to disable the auto TM generation + */ +class DisableAutoTm : public TcBase { + public: + DisableAutoTm(TcParams params) : TcBase(params) { + spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); + // spParams.creator.setApid(APID_AUTO_TM); + // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket() { + auto res = checkSizeAndSerializeHeader(); + if (res != returnvalue::OK) { + return res; + } + payloadStart[0] = DISABLE; + return calcAndSetCrc(); + } + + private: + static const uint16_t PAYLOAD_LENGTH = 1; // length without CRC field + static const uint8_t DISABLE = 0; +}; + +/** + * @brief This class creates the space packet to request the logging data from the supervisor + */ +class RequestLoggingData : public TcBase { + public: + /** + * Subapid + */ + enum class Sa : uint8_t { + REQUEST_COUNTERS = 1, /**< REQUEST_COUNTERS */ + REQUEST_EVENT_BUFFERS = 2, /**< REQUEST_EVENT_BUFFERS */ + CLEAR_COUNTERS = 3, /**< CLEAR_COUNTERS */ + SET_LOGGING_TOPIC = 4 /**< SET_LOGGING_TOPIC */ + }; + + RequestLoggingData(TcParams params) : TcBase(params) { + spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); + // spParams.creator.setApid(APID_REQUEST_LOGGING_DATA); + // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + /** + * @param sa + * @param tpc Topic + * @return + */ + ReturnValue_t buildPacket(Sa sa, uint8_t tpc = 0) { + auto res = checkSizeAndSerializeHeader(); + if (res != returnvalue::OK) { + return res; + } + payloadStart[0] = static_cast(sa); + payloadStart[1] = tpc; + return calcAndSetCrc(); + } + + private: + static const uint16_t PAYLOAD_LENGTH = 2; // length without CRC field + static const uint8_t TPC_OFFSET = 1; +}; + +typedef struct { + // The most significant bit of msec value is set to 0x80 to indicate that full + // time and data information is transmitted, when the time has been synced with + // the reference. If the time has not been synced with reference, then the most + // significant bit is set to 0x00. Only the most significant bit is used for + // this purpose (bit 15 of the field tm_msec) + uint16_t tm_msec; // miliseconds 0-999; + uint8_t tm_sec; // seconds after the minute, 0 to 60 + // (0 - 60 allows for the occasional leap second) + uint8_t tm_min; // minutes after the hour, 0 to 59 + uint8_t tm_hour; // hours since midnight, 0 to 23 + uint8_t tm_mday; // day of the month, 1 to 31 + uint8_t tm_mon; // months 1 to 12 + uint8_t tm_year; // years since 1900 +} tas_time_t; + +} // namespace notimpl + } // namespace supv #endif /* MISSION_DEVICES_DEVICEDEFINITIONS_PLOCSVPDEFINITIONS_H_ */ diff --git a/linux/devices/devicedefinitions/SupvReturnValuesIF.h b/linux/devices/devicedefinitions/SupvReturnValuesIF.h deleted file mode 100644 index f4557735..00000000 --- a/linux/devices/devicedefinitions/SupvReturnValuesIF.h +++ /dev/null @@ -1,61 +0,0 @@ -#ifndef SUPV_RETURN_VALUES_IF_H_ -#define SUPV_RETURN_VALUES_IF_H_ - -#include "fsfw/returnvalues/returnvalue.h" - -class SupvReturnValuesIF { - public: - static const uint8_t INTERFACE_ID = CLASS_ID::SUPV_RETURN_VALUES_IF; - - //! [EXPORT] : [COMMENT] Space Packet received from PLOC supervisor has invalid CRC - static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xA0); - //! [EXPORT] : [COMMENT] Received ACK failure reply from PLOC supervisor - static const ReturnValue_t RECEIVED_ACK_FAILURE = MAKE_RETURN_CODE(0xA1); - //! [EXPORT] : [COMMENT] Received execution failure reply from PLOC supervisor - static const ReturnValue_t RECEIVED_EXE_FAILURE = MAKE_RETURN_CODE(0xA2); - //! [EXPORT] : [COMMENT] Received space packet with invalid APID from PLOC supervisor - static const ReturnValue_t INVALID_APID = MAKE_RETURN_CODE(0xA3); - //! [EXPORT] : [COMMENT] Failed to read current system time - static const ReturnValue_t GET_TIME_FAILURE = MAKE_RETURN_CODE(0xA4); - //! [EXPORT] : [COMMENT] Received command with invalid watchdog parameter. Valid watchdogs are 0 - //! for PS, 1 for PL and 2 for INT - static const ReturnValue_t INVALID_WATCHDOG = MAKE_RETURN_CODE(0xA5); - //! [EXPORT] : [COMMENT] Received watchdog timeout config command with invalid timeout. Valid - //! timeouts must be in the range between 1000 and 360000 ms. - static const ReturnValue_t INVALID_WATCHDOG_TIMEOUT = MAKE_RETURN_CODE(0xA6); - //! [EXPORT] : [COMMENT] Received latchup config command with invalid latchup ID - static const ReturnValue_t INVALID_LATCHUP_ID = MAKE_RETURN_CODE(0xA7); - //! [EXPORT] : [COMMENT] Received set adc sweep period command with invalid sweep period. Must be - //! larger than 21. - static const ReturnValue_t SWEEP_PERIOD_TOO_SMALL = MAKE_RETURN_CODE(0xA8); - //! [EXPORT] : [COMMENT] Receive auto EM test command with invalid test param. Valid params are 1 - //! and 2. - static const ReturnValue_t INVALID_TEST_PARAM = MAKE_RETURN_CODE(0xA9); - //! [EXPORT] : [COMMENT] Returned when scanning for MRAM dump packets failed. - static const ReturnValue_t MRAM_PACKET_PARSING_FAILURE = MAKE_RETURN_CODE(0xAA); - //! [EXPORT] : [COMMENT] Returned when the start and stop addresses of the MRAM dump or MRAM wipe - //! commands are invalid (e.g. start address bigger than stop address) - static const ReturnValue_t INVALID_MRAM_ADDRESSES = MAKE_RETURN_CODE(0xAB); - //! [EXPORT] : [COMMENT] Expect reception of an MRAM dump packet but received space packet with - //! other apid. - static const ReturnValue_t NO_MRAM_PACKET = MAKE_RETURN_CODE(0xAC); - //! [EXPORT] : [COMMENT] Path to PLOC directory on SD card does not exist - static const ReturnValue_t PATH_DOES_NOT_EXIST = MAKE_RETURN_CODE(0xAD); - //! [EXPORT] : [COMMENT] MRAM dump file does not exists. The file should actually already have - //! been created with the reception of the first dump packet. - static const ReturnValue_t MRAM_FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xAE); - //! [EXPORT] : [COMMENT] Received action command has invalid length - static const ReturnValue_t INVALID_LENGTH = MAKE_RETURN_CODE(0xAF); - //! [EXPORT] : [COMMENT] Filename too long - static const ReturnValue_t FILENAME_TOO_LONG = MAKE_RETURN_CODE(0xB0); - //! [EXPORT] : [COMMENT] Received update status report with invalid packet length field - static const ReturnValue_t UPDATE_STATUS_REPORT_INVALID_LENGTH = MAKE_RETURN_CODE(0xB1); - //! [EXPORT] : [COMMENT] Update status report does not contain expected CRC. There might be a bit - //! flip in the update memory region. - static const ReturnValue_t UPDATE_CRC_FAILURE = MAKE_RETURN_CODE(0xB2); - //! [EXPORT] : [COMMENT] Supervisor helper task ist currently executing a command (wait until - //! helper tas has finished or interrupt by sending the terminate command) - static const ReturnValue_t SUPV_HELPER_EXECUTING = MAKE_RETURN_CODE(0xB3); -}; - -#endif /* SUPV_RETURN_VALUES_IF_H_ */ diff --git a/linux/devices/ploc/CMakeLists.txt b/linux/devices/ploc/CMakeLists.txt index f085eab3..67a0637b 100644 --- a/linux/devices/ploc/CMakeLists.txt +++ b/linux/devices/ploc/CMakeLists.txt @@ -1,4 +1,4 @@ target_sources( ${OBSW_NAME} PRIVATE PlocSupervisorHandler.cpp PlocMemoryDumper.cpp PlocMPSoCHandler.cpp - PlocMPSoCHelper.cpp PlocSupvHelper.cpp) + PlocMPSoCHelper.cpp PlocSupvUartMan.cpp) diff --git a/linux/devices/ploc/PlocMemoryDumper.h b/linux/devices/ploc/PlocMemoryDumper.h index da72c558..4a4e05bf 100644 --- a/linux/devices/ploc/PlocMemoryDumper.h +++ b/linux/devices/ploc/PlocMemoryDumper.h @@ -5,7 +5,12 @@ #include #include "OBSWConfig.h" + +#ifdef XIPHOS_Q7S #include "bsp_q7s/fs/SdCardManager.h" +#endif + +#include "eive/eventSubsystemIds.h" #include "fsfw/action/ActionHelper.h" #include "fsfw/action/CommandActionHelper.h" #include "fsfw/action/CommandsActionsIF.h" @@ -13,7 +18,7 @@ #include "fsfw/objectmanager/SystemObject.h" #include "fsfw/returnvalues/returnvalue.h" #include "fsfw/tasks/ExecutableObjectIF.h" -#include "linux/fsfwconfig/objects/systemObjectList.h" +#include "objects/systemObjectList.h" /** * @brief Because the buffer of the linux tty driver is limited to 2 x 65535 bytes, this class is diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 6bc224e6..08c63b1a 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -1,6 +1,8 @@ #include "PlocSupervisorHandler.h" #include +#include +#include #include #include @@ -14,11 +16,13 @@ #include "fsfw/ipc/QueueFactory.h" #include "fsfw/timemanager/Clock.h" -PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, - CookieIF* comCookie, Gpio uartIsolatorSwitch, - power::Switch_t powerSwitch, - PlocSupvHelper* supvHelper) - : DeviceHandlerBase(objectId, uartComIFid, comCookie), +using namespace supv; +using namespace returnvalue; + +PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, CookieIF* comCookie, + Gpio uartIsolatorSwitch, power::Switch_t powerSwitch, + PlocSupvUartManager& supvHelper) + : DeviceHandlerBase(objectId, supvHelper.getObjectId(), comCookie), uartIsolatorSwitch(uartIsolatorSwitch), hkset(this), bootStatusReport(this), @@ -26,13 +30,10 @@ PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t u loggingReport(this), adcReport(this), powerSwitch(powerSwitch), - supvHelper(supvHelper) { - if (comCookie == NULL) { + uartManager(supvHelper) { + if (comCookie == nullptr) { sif::error << "PlocSupervisorHandler: Invalid com cookie" << std::endl; } - if (supvHelper == nullptr) { - sif::error << "PlocSupervisorHandler: Invalid PlocSupvHelper object" << std::endl; - } spParams.buf = commandBuffer; spParams.maxSize = sizeof(commandBuffer); eventQueue = QueueFactory::instance()->createMessageQueue(EventMessage::EVENT_MESSAGE_SIZE * 5); @@ -46,23 +47,9 @@ ReturnValue_t PlocSupervisorHandler::initialize() { if (result != returnvalue::OK) { return result; } - uartComIf = dynamic_cast(communicationInterface); - if (uartComIf == nullptr) { - sif::warning << "PlocSupervisorHandler::initialize: Invalid uart com if" << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } -#ifndef TE0720_1CFA +#ifdef XIPHOS_Q7S sdcMan = SdCardManager::instance(); #endif /* TE0720_1CFA */ - if (supvHelper == nullptr) { - sif::warning << "PlocSupervisorHandler::initialize: Invalid supervisor helper" << std::endl; - return ObjectManagerIF::CHILD_INIT_FAILED; - } - result = supvHelper->setComIF(uartComIf); - if (result != returnvalue::OK) { - return ObjectManagerIF::CHILD_INIT_FAILED; - } - supvHelper->setComCookie(comCookie); result = eventSubscription(); if (result != returnvalue::OK) { @@ -94,16 +81,12 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, ReturnValue_t result = returnvalue::OK; switch (actionId) { - case TERMINATE_SUPV_HELPER: { - supvHelper->stopProcess(); - return EXECUTION_FINISHED; - } default: break; } - if (plocSupvHelperExecuting) { - return SupvReturnValuesIF::SUPV_HELPER_EXECUTING; + if (uartManager.longerRequestActive()) { + return result::SUPV_HELPER_EXECUTING; } result = acceptExternalDeviceCommands(); @@ -114,26 +97,27 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, switch (actionId) { case PERFORM_UPDATE: { if (size > config::MAX_PATH_SIZE + config::MAX_FILENAME_SIZE) { - return SupvReturnValuesIF::FILENAME_TOO_LONG; + return result::FILENAME_TOO_LONG; } + shutdownCmdSent = false; UpdateParams params; result = extractUpdateCommand(data, size, params); if (result != returnvalue::OK) { return result; } - result = supvHelper->performUpdate(params); + result = uartManager.performUpdate(params); if (result != returnvalue::OK) { return result; } - plocSupvHelperExecuting = true; return EXECUTION_FINISHED; } case CONTINUE_UPDATE: { - supvHelper->initiateUpdateContinuation(); - plocSupvHelperExecuting = true; + shutdownCmdSent = false; + uartManager.initiateUpdateContinuation(); return EXECUTION_FINISHED; } case MEMORY_CHECK_WITH_FILE: { + shutdownCmdSent = false; UpdateParams params; ReturnValue_t result = extractBaseParams(&data, size, params); if (result != returnvalue::OK) { @@ -142,20 +126,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, if (not std::filesystem::exists(params.file)) { return HasFileSystemIF::FILE_DOES_NOT_EXIST; } - supvHelper->performMemCheck(params.file, params.memId, params.startAddr); - plocSupvHelperExecuting = true; - return EXECUTION_FINISHED; - } - case LOGGING_REQUEST_EVENT_BUFFERS: { - if (size > config::MAX_PATH_SIZE) { - return SupvReturnValuesIF::FILENAME_TOO_LONG; - } - result = supvHelper->startEventbBufferRequest( - std::string(reinterpret_cast(data), size)); - if (result != returnvalue::OK) { - return result; - } - plocSupvHelperExecuting = true; + uartManager.performMemCheck(params.file, params.memId, params.startAddr); return EXECUTION_FINISHED; } default: @@ -166,27 +137,19 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, void PlocSupervisorHandler::doStartUp() { if (setTimeDuringStartup) { - switch (startupState) { - case StartupState::OFF: { - bootTimeout.resetTimer(); - startupState = StartupState::BOOTING; - break; + if (startupState == StartupState::OFF) { + bootTimeout.resetTimer(); + startupState = StartupState::BOOTING; + } + if (startupState == StartupState::BOOTING) { + if (bootTimeout.hasTimedOut()) { + uartIsolatorSwitch.pullHigh(); + uartManager.start(); + startupState = StartupState::SET_TIME; } - case StartupState::BOOTING: { - if (bootTimeout.hasTimedOut()) { - uartIsolatorSwitch.pullHigh(); - startupState = StartupState::SET_TIME; - } - break; - } - case StartupState::SET_TIME_EXECUTING: - break; - case StartupState::ON: { - setMode(_MODE_TO_ON); - break; - } - default: - break; + } + if (startupState == StartupState::ON) { + setMode(_MODE_TO_ON); } } else { uartIsolatorSwitch.pullHigh(); @@ -196,6 +159,7 @@ void PlocSupervisorHandler::doStartUp() { void PlocSupervisorHandler::doShutDown() { setMode(_MODE_POWER_DOWN); + uartManager.stop(); uartIsolatorSwitch.pullLow(); startupState = StartupState::OFF; } @@ -221,17 +185,17 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d spParams.buf = commandBuffer; switch (deviceCommand) { case GET_HK_REPORT: { - prepareEmptyCmd(APID_GET_HK_REPORT); + prepareEmptyCmd(Apid::HK, static_cast(tc::HkId::GET_REPORT)); result = returnvalue::OK; break; } case START_MPSOC: { - prepareEmptyCmd(APID_START_MPSOC); + prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::START_MPSOC)); result = returnvalue::OK; break; } case SHUTDOWN_MPSOC: { - prepareEmptyCmd(APID_SHUTWOWN_MPSOC); + prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::SHUTDOWN_MPSOC)); result = returnvalue::OK; break; } @@ -241,7 +205,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case RESET_MPSOC: { - prepareEmptyCmd(APID_RESET_MPSOC); + prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::RESET_MPSOC)); result = returnvalue::OK; break; } @@ -265,7 +229,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case GET_BOOT_STATUS_REPORT: { - prepareEmptyCmd(APID_GET_BOOT_STATUS_RPT); + prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::GET_BOOT_STATUS_REPORT)); result = returnvalue::OK; break; } @@ -281,6 +245,44 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d result = prepareSetAlertLimitCmd(commandData); break; } + case GET_LATCHUP_STATUS_REPORT: { + prepareEmptyCmd(Apid::LATCHUP_MON, static_cast(tc::LatchupMonId::GET_STATUS_REPORT)); + result = returnvalue::OK; + break; + } + case RUN_AUTO_EM_TESTS: { + result = prepareRunAutoEmTest(commandData); + break; + } + case SET_GPIO: { + prepareSetGpioCmd(commandData); + result = returnvalue::OK; + break; + } + case FACTORY_RESET: { + result = prepareFactoryResetCmd(commandData, commandDataLen); + break; + } + case READ_GPIO: { + prepareReadGpioCmd(commandData); + result = returnvalue::OK; + break; + } + case SET_SHUTDOWN_TIMEOUT: { + prepareSetShutdownTimeoutCmd(commandData); + result = returnvalue::OK; + break; + } + case FACTORY_FLASH: { + prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::FACTORY_FLASH)); + result = returnvalue::OK; + break; + } + case RESET_PL: { + prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::RESET_PL)); + result = returnvalue::OK; + break; + } case SET_ADC_ENABLED_CHANNELS: { prepareSetAdcEnabledChannelsCmd(commandData); result = returnvalue::OK; @@ -296,224 +298,145 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d result = returnvalue::OK; break; } - case GET_LATCHUP_STATUS_REPORT: { - prepareEmptyCmd(APID_GET_LATCHUP_STATUS_REPORT); - result = returnvalue::OK; - break; - } - case COPY_ADC_DATA_TO_MRAM: { - prepareEmptyCmd(APID_COPY_ADC_DATA_TO_MRAM); - result = returnvalue::OK; - break; - } - case REQUEST_ADC_REPORT: { - prepareEmptyCmd(APID_REQUEST_ADC_REPORT); - result = returnvalue::OK; - break; - } - case RUN_AUTO_EM_TESTS: { - result = prepareRunAutoEmTest(commandData); - break; - } case WIPE_MRAM: { result = prepareWipeMramCmd(commandData); break; } - case FIRST_MRAM_DUMP: - case CONSECUTIVE_MRAM_DUMP: - result = prepareDumpMramCmd(commandData); - break; - case SET_GPIO: { - prepareSetGpioCmd(commandData); - result = returnvalue::OK; - break; - } - case READ_GPIO: { - prepareReadGpioCmd(commandData); - result = returnvalue::OK; - break; - } - case RESTART_SUPERVISOR: { - prepareEmptyCmd(APID_RESTART_SUPERVISOR); - result = returnvalue::OK; - break; - } - case FACTORY_RESET_CLEAR_ALL: { - FactoryReset packet(spParams); - result = packet.buildPacket(FactoryReset::Op::CLEAR_ALL); - if (result != returnvalue::OK) { - break; - } - finishTcPrep(packet.getFullPacketLen()); - break; - } - case FACTORY_RESET_CLEAR_MIRROR: { - FactoryReset packet(spParams); - result = packet.buildPacket(FactoryReset::Op::MIRROR_ENTRIES); - if (result != returnvalue::OK) { - break; - } - finishTcPrep(packet.getFullPacketLen()); - break; - } - case FACTORY_RESET_CLEAR_CIRCULAR: { - FactoryReset packet(spParams); - result = packet.buildPacket(FactoryReset::Op::CIRCULAR_ENTRIES); - if (result != returnvalue::OK) { - break; - } - finishTcPrep(packet.getFullPacketLen()); - break; - } - case START_MPSOC_QUIET: { - prepareEmptyCmd(APID_START_MPSOC_QUIET); - result = returnvalue::OK; - break; - } - case SET_SHUTDOWN_TIMEOUT: { - prepareSetShutdownTimeoutCmd(commandData); - result = returnvalue::OK; - break; - } - case FACTORY_FLASH: { - prepareEmptyCmd(APID_FACTORY_FLASH); - result = returnvalue::OK; - break; - } - case ENABLE_AUTO_TM: { - EnableAutoTm packet(spParams); - result = packet.buildPacket(); - if (result != returnvalue::OK) { - break; - } - finishTcPrep(packet.getFullPacketLen()); - break; - } - case DISABLE_AUTO_TM: { - DisableAutoTm packet(spParams); - result = packet.buildPacket(); - if (result != returnvalue::OK) { - break; - } - finishTcPrep(packet.getFullPacketLen()); - break; - } - case LOGGING_REQUEST_COUNTERS: { - RequestLoggingData packet(spParams); - result = packet.buildPacket(RequestLoggingData::Sa::REQUEST_COUNTERS); - if (result != returnvalue::OK) { - break; - } - finishTcPrep(packet.getFullPacketLen()); - break; - } - case LOGGING_CLEAR_COUNTERS: { - RequestLoggingData packet(spParams); - result = packet.buildPacket(RequestLoggingData::Sa::CLEAR_COUNTERS); - if (result != returnvalue::OK) { - break; - } - finishTcPrep(packet.getFullPacketLen()); - break; - } - case LOGGING_SET_TOPIC: { - if (commandData == nullptr or commandDataLen == 0) { - return HasActionsIF::INVALID_PARAMETERS; - } - uint8_t tpc = *(commandData); - RequestLoggingData packet(spParams); - result = packet.buildPacket(RequestLoggingData::Sa::SET_LOGGING_TOPIC, tpc); - if (result != returnvalue::OK) { - break; - } - finishTcPrep(packet.getFullPacketLen()); - break; - } - case RESET_PL: { - prepareEmptyCmd(APID_RESET_PL); - result = returnvalue::OK; - break; - } - case ENABLE_NVMS: { - result = prepareEnableNvmsCommand(commandData); - break; - } + // case ENABLE_NVMS: { + // result = prepareEnableNvmsCommand(commandData); + // break; + // } + // case RESTART_SUPERVISOR: { + // prepareEmptyCmd(APID_RESTART_SUPERVISOR); + // result = returnvalue::OK; + // break; + // } + // Removed command + // case START_MPSOC_QUIET: { + // prepareEmptyCmd(APID_START_MPSOC_QUIET); + // result = returnvalue::OK; + // break; + // } + // case ENABLE_AUTO_TM: { + // EnableAutoTm packet(spParams); + // result = packet.buildPacket(); + // if (result != returnvalue::OK) { + // break; + // } + // finishTcPrep(packet.getFullPacketLen()); + // break; + // } + // case DISABLE_AUTO_TM: { + // DisableAutoTm packet(spParams); + // result = packet.buildPacket(); + // if (result != returnvalue::OK) { + // break; + // } + // finishTcPrep(packet.getFullPacketLen()); + // break; + // } + // case LOGGING_REQUEST_COUNTERS: { + // RequestLoggingData packet(spParams); + // result = packet.buildPacket(RequestLoggingData::Sa::REQUEST_COUNTERS); + // if (result != returnvalue::OK) { + // break; + // } + // finishTcPrep(packet.getFullPacketLen()); + // break; + // } + // case LOGGING_CLEAR_COUNTERS: { + // RequestLoggingData packet(spParams); + // result = packet.buildPacket(RequestLoggingData::Sa::CLEAR_COUNTERS); + // if (result != returnvalue::OK) { + // break; + // } + // finishTcPrep(packet.getFullPacketLen()); + // break; + // } + // case LOGGING_SET_TOPIC: { + // if (commandData == nullptr or commandDataLen == 0) { + // return HasActionsIF::INVALID_PARAMETERS; + // } + // uint8_t tpc = *(commandData); + // RequestLoggingData packet(spParams); + // result = packet.buildPacket(RequestLoggingData::Sa::SET_LOGGING_TOPIC, tpc); + // if (result != returnvalue::OK) { + // break; + // } + // finishTcPrep(packet.getFullPacketLen()); + // break; + // } + // I think this is disabled right now according to the TC excel table + // case COPY_ADC_DATA_TO_MRAM: { + // prepareEmptyCmd(APID_COPY_ADC_DATA_TO_MRAM); + // result = returnvalue::OK; + // break; + // } + // case REQUEST_ADC_REPORT: { + // prepareEmptyCmd(APID_REQUEST_ADC_REPORT); + // result = returnvalue::OK; + // break; + // } + // case FIRST_MRAM_DUMP: + // case CONSECUTIVE_MRAM_DUMP: + // result = prepareDumpMramCmd(commandData); + // break; default: sif::debug << "PlocSupervisorHandler::buildCommandFromCommand: Command not implemented" << std::endl; result = DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED; break; } - - if (result == returnvalue::OK) { - /** - * Flushing the receive buffer to make sure there are no data left from a faulty reply. - */ - uartComIf->flushUartRxBuffer(comCookie); - } - return result; } void PlocSupervisorHandler::fillCommandAndReplyMap() { - using namespace supv; - this->insertInCommandMap(GET_HK_REPORT); - this->insertInCommandMap(START_MPSOC); - this->insertInCommandMap(SHUTDOWN_MPSOC); - this->insertInCommandMap(SEL_MPSOC_BOOT_IMAGE); - this->insertInCommandMap(SET_BOOT_TIMEOUT); - this->insertInCommandMap(SET_MAX_RESTART_TRIES); - this->insertInCommandMap(RESET_MPSOC); - this->insertInCommandMap(SET_TIME_REF); - this->insertInCommandMap(DISABLE_PERIOIC_HK_TRANSMISSION); - this->insertInCommandMap(GET_BOOT_STATUS_REPORT); - this->insertInCommandMap(ENABLE_LATCHUP_ALERT); - this->insertInCommandMap(DISABLE_LATCHUP_ALERT); - this->insertInCommandMap(SET_ALERT_LIMIT); - this->insertInCommandMap(SET_ADC_ENABLED_CHANNELS); - this->insertInCommandMap(SET_ADC_WINDOW_AND_STRIDE); - this->insertInCommandMap(SET_ADC_THRESHOLD); - this->insertInCommandMap(GET_LATCHUP_STATUS_REPORT); - this->insertInCommandMap(COPY_ADC_DATA_TO_MRAM); - this->insertInCommandMap(REQUEST_ADC_REPORT); - this->insertInCommandMap(RUN_AUTO_EM_TESTS); - this->insertInCommandMap(WIPE_MRAM); - this->insertInCommandMap(SET_GPIO); - this->insertInCommandMap(READ_GPIO); - this->insertInCommandMap(RESTART_SUPERVISOR); - this->insertInCommandMap(FACTORY_RESET_CLEAR_ALL); - this->insertInCommandMap(FACTORY_RESET_CLEAR_MIRROR); - this->insertInCommandMap(FACTORY_RESET_CLEAR_CIRCULAR); - this->insertInCommandMap(START_MPSOC_QUIET); - this->insertInCommandMap(SET_SHUTDOWN_TIMEOUT); - this->insertInCommandMap(FACTORY_FLASH); - this->insertInCommandMap(ENABLE_AUTO_TM); - this->insertInCommandMap(DISABLE_AUTO_TM); - this->insertInCommandMap(LOGGING_REQUEST_COUNTERS); - this->insertInCommandMap(LOGGING_CLEAR_COUNTERS); - this->insertInCommandMap(LOGGING_SET_TOPIC); - this->insertInCommandMap(RESET_PL); - this->insertInCommandMap(ENABLE_NVMS); - this->insertInCommandAndReplyMap(FIRST_MRAM_DUMP, 0, nullptr, 0, false, false, FIRST_MRAM_DUMP, - &mramDumpTimeout); - this->insertInCommandAndReplyMap(CONSECUTIVE_MRAM_DUMP, 0, nullptr, 0, false, false, - CONSECUTIVE_MRAM_DUMP, &mramDumpTimeout); - this->insertInReplyMap(ACK_REPORT, 3, nullptr, SIZE_ACK_REPORT, false, - &acknowledgementReportTimeout); - this->insertInReplyMap(EXE_REPORT, 0, nullptr, SIZE_EXE_REPORT, false, &executionReportTimeout); - this->insertInReplyMap(HK_REPORT, 3, &hkset, SIZE_HK_REPORT); - this->insertInReplyMap(BOOT_STATUS_REPORT, 3, &bootStatusReport, SIZE_BOOT_STATUS_REPORT); - this->insertInReplyMap(LATCHUP_REPORT, 3, &latchupStatusReport, SIZE_LATCHUP_STATUS_REPORT); - this->insertInReplyMap(LOGGING_REPORT, 3, &loggingReport, SIZE_LOGGING_REPORT); - this->insertInReplyMap(ADC_REPORT, 3, &adcReport, SIZE_ADC_REPORT); + // Command only + insertInCommandMap(GET_HK_REPORT); + insertInCommandMap(START_MPSOC); + insertInCommandMap(SHUTDOWN_MPSOC); + insertInCommandMap(SEL_MPSOC_BOOT_IMAGE); + insertInCommandMap(SET_BOOT_TIMEOUT); + insertInCommandMap(SET_MAX_RESTART_TRIES); + insertInCommandMap(RESET_MPSOC); + insertInCommandMap(WIPE_MRAM); + insertInCommandMap(SET_TIME_REF); + insertInCommandMap(DISABLE_PERIOIC_HK_TRANSMISSION); + insertInCommandMap(GET_BOOT_STATUS_REPORT); + insertInCommandMap(ENABLE_LATCHUP_ALERT); + insertInCommandMap(DISABLE_LATCHUP_ALERT); + insertInCommandMap(SET_ALERT_LIMIT); + insertInCommandMap(GET_LATCHUP_STATUS_REPORT); + insertInCommandMap(RUN_AUTO_EM_TESTS); + insertInCommandMap(SET_GPIO); + insertInCommandMap(READ_GPIO); + insertInCommandMap(FACTORY_RESET); + insertInCommandMap(MEMORY_CHECK); + insertInCommandMap(SET_SHUTDOWN_TIMEOUT); + insertInCommandMap(FACTORY_FLASH); + insertInCommandMap(SET_ADC_ENABLED_CHANNELS); + insertInCommandMap(SET_ADC_THRESHOLD); + insertInCommandMap(SET_ADC_WINDOW_AND_STRIDE); + insertInCommandMap(RESET_PL); + + // ACK replies, use countdown for them + insertInReplyMap(ACK_REPORT, 0, nullptr, SIZE_ACK_REPORT, false, &acknowledgementReportTimeout); + insertInReplyMap(EXE_REPORT, 0, nullptr, SIZE_EXE_REPORT, false, &executionReportTimeout); + insertInReplyMap(MEMORY_CHECK, 5, nullptr, 0, false); + + // TM replies + insertInReplyMap(HK_REPORT, 3, &hkset, SIZE_HK_REPORT); + insertInReplyMap(BOOT_STATUS_REPORT, 3, &bootStatusReport, SIZE_BOOT_STATUS_REPORT); + insertInReplyMap(LATCHUP_REPORT, 3, &latchupStatusReport, SIZE_LATCHUP_STATUS_REPORT); + insertInReplyMap(LOGGING_REPORT, 3, &loggingReport, SIZE_LOGGING_REPORT); + insertInReplyMap(ADC_REPORT, 3, &adcReport, SIZE_ADC_REPORT); } ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::iterator command, uint8_t expectedReplies, bool useAlternateId, DeviceCommandId_t alternateReplyID) { - using namespace supv; - ReturnValue_t result = returnvalue::OK; + ReturnValue_t result = OK; uint8_t enabledReplies = 0; @@ -586,6 +509,16 @@ ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::ite } break; } + case MEMORY_CHECK: { + enabledReplies = 3; + result = + DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true, MEMORY_CHECK); + if (result != returnvalue::OK) { + sif::debug << "PlocSupervisorHandler::enableReplyInReplyMap: Reply with id " << MEMORY_CHECK + << " not in replyMap" << std::endl; + } + break; + } case START_MPSOC: case SHUTDOWN_MPSOC: case SEL_MPSOC_BOOT_IMAGE: @@ -599,25 +532,23 @@ ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::ite case SET_ADC_ENABLED_CHANNELS: case SET_ADC_WINDOW_AND_STRIDE: case SET_ADC_THRESHOLD: - case COPY_ADC_DATA_TO_MRAM: + // case COPY_ADC_DATA_TO_MRAM: case RUN_AUTO_EM_TESTS: case WIPE_MRAM: case SET_GPIO: + case FACTORY_RESET: case READ_GPIO: - case RESTART_SUPERVISOR: - case FACTORY_RESET_CLEAR_ALL: - case FACTORY_RESET_CLEAR_MIRROR: - case FACTORY_RESET_CLEAR_CIRCULAR: + // case RESTART_SUPERVISOR: case DISABLE_PERIOIC_HK_TRANSMISSION: - case START_MPSOC_QUIET: + // case START_MPSOC_QUIET: case SET_SHUTDOWN_TIMEOUT: case FACTORY_FLASH: case ENABLE_AUTO_TM: case DISABLE_AUTO_TM: - case LOGGING_CLEAR_COUNTERS: - case LOGGING_SET_TOPIC: + // case LOGGING_CLEAR_COUNTERS: + // case LOGGING_SET_TOPIC: case RESET_PL: - case ENABLE_NVMS: + // case ENABLE_NVMS: enabledReplies = 2; break; default: @@ -649,73 +580,70 @@ ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::ite ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId, size_t* foundLen) { using namespace supv; - if (nextReplyId == FIRST_MRAM_DUMP) { - *foundId = FIRST_MRAM_DUMP; - return parseMramPackets(start, remainingSize, foundLen); - } else if (nextReplyId == CONSECUTIVE_MRAM_DUMP) { - *foundId = CONSECUTIVE_MRAM_DUMP; - return parseMramPackets(start, remainingSize, foundLen); - } + // TODO: Is this still required? + // if (nextReplyId == FIRST_MRAM_DUMP) { + // *foundId = FIRST_MRAM_DUMP; + // return parseMramPackets(start, remainingSize, foundLen); + // } else if (nextReplyId == CONSECUTIVE_MRAM_DUMP) { + // *foundId = CONSECUTIVE_MRAM_DUMP; + // return parseMramPackets(start, remainingSize, foundLen); + // } - ReturnValue_t result = returnvalue::OK; - - uint16_t apid = (*(start) << 8 | *(start + 1)) & APID_MASK; + tmReader.setData(start, remainingSize); + // sif::debug << "PlocSupervisorHandler::scanForReply: Received Packet" << std::endl; + // arrayprinter::print(start, remainingSize); + uint16_t apid = tmReader.getModuleApid(); switch (apid) { - case (APID_ACK_SUCCESS): - *foundLen = SIZE_ACK_REPORT; - *foundId = ACK_REPORT; + case (Apid::TMTC_MAN): { + switch (tmReader.getServiceId()) { + case (static_cast(supv::tm::TmtcId::ACK)): + case (static_cast(supv::tm::TmtcId::NAK)): { + *foundLen = tmReader.getFullPacketLen(); + *foundId = ReplyId::ACK_REPORT; + return OK; + } + case (static_cast(supv::tm::TmtcId::EXEC_ACK)): + case (static_cast(supv::tm::TmtcId::EXEC_NAK)): { + *foundLen = tmReader.getFullPacketLen(); + *foundId = EXE_REPORT; + return OK; + } + } break; - case (APID_ACK_FAILURE): - *foundLen = SIZE_ACK_REPORT; - *foundId = ACK_REPORT; + } + case (Apid::HK): { + if (tmReader.getServiceId() == static_cast(supv::tm::HkId::REPORT)) { + *foundLen = tmReader.getFullPacketLen(); + *foundId = ReplyId::HK_REPORT; + return OK; + } else if (tmReader.getServiceId() == static_cast(supv::tm::HkId::HARDFAULTS)) { + handleBadApidServiceCombination(SUPV_UNINIMPLEMENTED_TM, apid, tmReader.getServiceId()); + return INVALID_DATA; + } break; - case (APID_HK_REPORT): - *foundLen = SIZE_HK_REPORT; - *foundId = HK_REPORT; + } + case (Apid::BOOT_MAN): { + if (tmReader.getServiceId() == + static_cast(supv::tm::BootManId::BOOT_STATUS_REPORT)) { + *foundLen = tmReader.getFullPacketLen(); + *foundId = ReplyId::BOOT_STATUS_REPORT; + return OK; + } break; - case (APID_BOOT_STATUS_REPORT): - *foundLen = SIZE_BOOT_STATUS_REPORT; - *foundId = BOOT_STATUS_REPORT; - break; - case (APID_LATCHUP_STATUS_REPORT): - *foundLen = SIZE_LATCHUP_STATUS_REPORT; - *foundId = LATCHUP_REPORT; - break; - case (APID_DATA_LOGGER_DATA): - *foundLen = SIZE_LOGGING_REPORT; - *foundId = LOGGING_REPORT; - break; - case (APID_ADC_REPORT): - *foundLen = SIZE_ADC_REPORT; - *foundId = ADC_REPORT; - break; - case (APID_EXE_SUCCESS): - *foundLen = SIZE_EXE_REPORT; - *foundId = EXE_REPORT; - break; - case (APID_EXE_FAILURE): - *foundLen = SIZE_EXE_REPORT; - *foundId = EXE_REPORT; - break; - default: { - sif::debug << "PlocSupervisorHandler::scanForReply: Reply has invalid apid" << std::endl; - *foundLen = remainingSize; - return SupvReturnValuesIF::INVALID_APID; + } + case (Apid::MEM_MAN): { + if (tmReader.getServiceId() == + static_cast(supv::tm::MemManId::UPDATE_STATUS_REPORT)) { + *foundLen = tmReader.getFullPacketLen(); + *foundId = ReplyId::UPDATE_STATUS_REPORT; + return OK; + } } } - - return result; -} - -ReturnValue_t PlocSupervisorHandler::getSwitches(const uint8_t** switches, - uint8_t* numberOfSwitches) { - if (powerSwitch == power::NO_SWITCH) { - return DeviceHandlerBase::NO_SWITCH; - } - *numberOfSwitches = 1; - *switches = &powerSwitch; - return returnvalue::OK; + handleBadApidServiceCombination(SUPV_UNKNOWN_TM, apid, tmReader.getServiceId()); + *foundLen = remainingSize; + return INVALID_DATA; } ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id, @@ -740,22 +668,18 @@ ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id, result = handleLatchupStatusReport(packet); break; } - case (LOGGING_REPORT): { - result = handleLoggingReport(packet); - break; - } case (ADC_REPORT): { result = handleAdcReport(packet); break; } - case (FIRST_MRAM_DUMP): - case (CONSECUTIVE_MRAM_DUMP): - result = handleMramDumpPacket(id); - break; case (EXE_REPORT): { result = handleExecutionReport(packet); break; } + case (UPDATE_STATUS_REPORT): { + // TODO: handle status report here + break; + } default: { sif::debug << "PlocSupervisorHandler::interpretDeviceReply: Unknown device reply id" << std::endl; @@ -766,12 +690,6 @@ ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id, return result; } -void PlocSupervisorHandler::setNormalDatapoolEntriesInvalid() {} - -uint32_t PlocSupervisorHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { - return 7000; -} - ReturnValue_t PlocSupervisorHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) { localDataPoolMap.emplace(supv::NUM_TMS, new PoolEntry({0})); @@ -873,22 +791,26 @@ void PlocSupervisorHandler::handleEvent(EventMessage* eventMessage) { Event event = eventMessage->getEvent(); switch (objectId) { case objects::PLOC_SUPERVISOR_HELPER: { - plocSupvHelperExecuting = false; // After execution of update procedure, PLOC is in a state where it draws approx. 700 mA of // current. To leave this state the shutdown MPSoC command must be sent here. - if (event == PlocSupvHelper::SUPV_UPDATE_FAILED || - event == PlocSupvHelper::SUPV_UPDATE_SUCCESSFUL || - event == PlocSupvHelper::SUPV_CONTINUE_UPDATE_FAILED || - event == PlocSupvHelper::SUPV_CONTINUE_UPDATE_SUCCESSFUL || - event == PlocSupvHelper::SUPV_MEM_CHECK_FAIL || - event == PlocSupvHelper::SUPV_MEM_CHECK_OK) { - result = this->executeAction(supv::SHUTDOWN_MPSOC, NO_COMMANDER, nullptr, 0); - if (result != returnvalue::OK) { - triggerEvent(SUPV_MPSOC_SHUWDOWN_BUILD_FAILED); - sif::warning << "PlocSupervisorHandler::handleEvent: Failed to build MPSoC shutdown " - "command" - << std::endl; - return; + if (event == PlocSupvUartManager::SUPV_UPDATE_FAILED || + event == PlocSupvUartManager::SUPV_UPDATE_SUCCESSFUL || + event == PlocSupvUartManager::SUPV_CONTINUE_UPDATE_FAILED || + event == PlocSupvUartManager::SUPV_CONTINUE_UPDATE_SUCCESSFUL || + event == PlocSupvUartManager::SUPV_MEM_CHECK_FAIL || + event == PlocSupvUartManager::SUPV_MEM_CHECK_OK) { + // Wait for a short period for the uart state machine to adjust + // TaskFactory::delayTask(5); + if (not shutdownCmdSent) { + shutdownCmdSent = true; + result = this->executeAction(supv::SHUTDOWN_MPSOC, NO_COMMANDER, nullptr, 0); + if (result != returnvalue::OK) { + triggerEvent(SUPV_MPSOC_SHUTDOWN_BUILD_FAILED); + sif::warning << "PlocSupervisorHandler::handleEvent: Failed to build MPSoC shutdown " + "command" + << std::endl; + return; + } } } break; @@ -917,7 +839,7 @@ void PlocSupervisorHandler::setExecutionTimeout(DeviceCommandId_t command) { ReturnValue_t PlocSupervisorHandler::verifyPacket(const uint8_t* start, size_t foundLen) { if (CRC::crc16ccitt(start, foundLen) != 0) { - return SupvReturnValuesIF::CRC_FAILURE; + return result::CRC_FAILURE; } return returnvalue::OK; } @@ -926,55 +848,38 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) { using namespace supv; ReturnValue_t result = returnvalue::OK; - AcknowledgmentReport ack(data, SIZE_ACK_REPORT); - result = ack.checkSize(); - if (result != returnvalue::OK) { - return result; - } - - result = ack.checkCrc(); - if (result != returnvalue::OK) { + if (not tmReader.verifyCrc()) { sif::error << "PlocSupervisorHandler::handleAckReport: CRC failure" << std::endl; nextReplyId = supv::NONE; replyRawReplyIfnotWiretapped(data, supv::SIZE_ACK_REPORT); triggerEvent(SUPV_CRC_FAILURE_EVENT); - sendFailureReport(supv::ACK_REPORT, SupvReturnValuesIF::CRC_FAILURE); + sendFailureReport(supv::ACK_REPORT, result::CRC_FAILURE); disableAllReplies(); return returnvalue::OK; } - - result = ack.checkApid(); - - switch (result) { - case SupvReturnValuesIF::RECEIVED_ACK_FAILURE: { - DeviceCommandId_t commandId = getPendingCommand(); - if (commandId != DeviceHandlerIF::NO_COMMAND_ID) { - triggerEvent(SUPV_ACK_FAILURE, commandId, static_cast(ack.getStatusCode())); - } - printAckFailureInfo(ack.getStatusCode(), commandId); - sendFailureReport(supv::ACK_REPORT, SupvReturnValuesIF::RECEIVED_ACK_FAILURE); - disableAllReplies(); - nextReplyId = supv::NONE; - result = IGNORE_REPLY_DATA; - break; - } - case returnvalue::OK: { - setNextReplyId(); - break; - } - case SupvReturnValuesIF::INVALID_APID: - sif::warning << "PlocSupervisorHandler::handleAckReport: Invalid APID in Ack report" - << std::endl; - sendFailureReport(supv::ACK_REPORT, result); - disableAllReplies(); - nextReplyId = supv::NONE; - result = IGNORE_REPLY_DATA; - break; - default: { - sif::error << "PlocSupervisorHandler::handleAckReport: APID parsing failed" << std::endl; - result = returnvalue::FAILED; - break; + AcknowledgmentReport ack(tmReader); + result = ack.parse(); + if (result != returnvalue::OK) { + nextReplyId = supv::NONE; + replyRawReplyIfnotWiretapped(data, supv::SIZE_ACK_REPORT); + triggerEvent(SUPV_CRC_FAILURE_EVENT); + sendFailureReport(supv::ACK_REPORT, result); + disableAllReplies(); + return result; + } + if (tmReader.getServiceId() == static_cast(supv::tm::TmtcId::NAK)) { + DeviceCommandId_t commandId = getPendingCommand(); + if (commandId != DeviceHandlerIF::NO_COMMAND_ID) { + triggerEvent(SUPV_ACK_FAILURE, commandId, static_cast(ack.getStatusCode())); } + ack.printStatusInformation(); + printAckFailureInfo(ack.getStatusCode(), commandId); + sendFailureReport(supv::ACK_REPORT, result::RECEIVED_ACK_FAILURE); + disableAllReplies(); + nextReplyId = supv::NONE; + result = IGNORE_REPLY_DATA; + } else if (tmReader.getServiceId() == static_cast(supv::tm::TmtcId::ACK)) { + setNextReplyId(); } return result; } @@ -983,36 +888,20 @@ ReturnValue_t PlocSupervisorHandler::handleExecutionReport(const uint8_t* data) using namespace supv; ReturnValue_t result = returnvalue::OK; - ExecutionReport exe(data, SIZE_EXE_REPORT); - result = exe.checkSize(); - if (result != returnvalue::OK) { - return result; + if (not tmReader.verifyCrc()) { + nextReplyId = supv::NONE; + return result::CRC_FAILURE; } - - result = exe.checkCrc(); - if (result != returnvalue::OK) { - sif::error << "PlocSupervisorHandler::handleExecutionReport: CRC failure" << std::endl; + ExecutionReport report(tmReader); + result = report.parse(); + if (result != OK) { nextReplyId = supv::NONE; return result; } - - result = exe.checkApid(); - - switch (result) { - case (returnvalue::OK): { - handleExecutionSuccessReport(data); - break; - } - case (SupvReturnValuesIF::RECEIVED_EXE_FAILURE): { - handleExecutionFailureReport(exe.getStatusCode()); - result = returnvalue::OK; - break; - } - default: { - sif::error << "PlocSupervisorHandler::handleExecutionReport: Unknown APID" << std::endl; - result = returnvalue::FAILED; - break; - } + if (tmReader.getServiceId() == static_cast(supv::tm::TmtcId::EXEC_ACK)) { + result = handleExecutionSuccessReport(report); + } else if (tmReader.getServiceId() == static_cast(supv::tm::TmtcId::EXEC_NAK)) { + handleExecutionFailureReport(report); } nextReplyId = supv::NONE; return result; @@ -1023,12 +912,12 @@ ReturnValue_t PlocSupervisorHandler::handleHkReport(const uint8_t* data) { result = verifyPacket(data, supv::SIZE_HK_REPORT); - if (result == SupvReturnValuesIF::CRC_FAILURE) { + if (result == result::CRC_FAILURE) { sif::error << "PlocSupervisorHandler::handleHkReport: Hk report has invalid crc" << std::endl; return result; } - uint16_t offset = supv::DATA_FIELD_OFFSET; + uint16_t offset = supv::PAYLOAD_OFFSET; hkset.tempPs = *(data + offset) << 24 | *(data + offset + 1) << 16 | *(data + offset + 2) << 8 | *(data + offset + 3); offset += 4; @@ -1097,37 +986,40 @@ ReturnValue_t PlocSupervisorHandler::handleHkReport(const uint8_t* data) { ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data) { ReturnValue_t result = returnvalue::OK; - result = verifyPacket(data, supv::SIZE_BOOT_STATUS_REPORT); + result = verifyPacket(data, tmReader.getFullPacketLen()); - if (result == SupvReturnValuesIF::CRC_FAILURE) { + if (result == result::CRC_FAILURE) { sif::error << "PlocSupervisorHandler::handleBootStatusReport: Boot status report has invalid" " crc" << std::endl; return result; } - uint16_t offset = supv::DATA_FIELD_OFFSET; - bootStatusReport.socState = *(data + offset); + const uint8_t* payloadStart = tmReader.getPayloadStart(); + uint16_t offset = 0; + bootStatusReport.socState = payloadStart[0]; offset += 1; - bootStatusReport.powerCycles = *(data + offset); + bootStatusReport.powerCycles = payloadStart[1]; offset += 1; - bootStatusReport.bootAfterMs = *(data + offset) << 24 | *(data + offset + 1) << 16 | - *(data + offset + 2) << 8 | *(data + offset + 3); + bootStatusReport.bootAfterMs = *(payloadStart + offset) << 24 | + *(payloadStart + offset + 1) << 16 | + *(payloadStart + offset + 2) << 8 | *(payloadStart + offset + 3); offset += 4; - bootStatusReport.bootTimeoutMs = *(data + offset) << 24 | *(data + offset + 1) << 16 | - *(data + offset + 2) << 8 | *(data + offset + 3); + bootStatusReport.bootTimeoutMs = *(payloadStart + offset) << 24 | + *(payloadStart + offset + 1) << 16 | + *(payloadStart + offset + 2) << 8 | *(payloadStart + offset + 3); offset += 4; - bootStatusReport.activeNvm = *(data + offset); + bootStatusReport.activeNvm = *(payloadStart + offset); offset += 1; - bootStatusReport.bp0State = *(data + offset); + bootStatusReport.bp0State = *(payloadStart + offset); offset += 1; - bootStatusReport.bp1State = *(data + offset); + bootStatusReport.bp1State = *(payloadStart + offset); offset += 1; - bootStatusReport.bp2State = *(data + offset); + bootStatusReport.bp2State = *(payloadStart + offset); offset += 1; - bootStatusReport.bootState = *(data + offset); + bootStatusReport.bootState = *(payloadStart + offset); offset += 1; - bootStatusReport.bootCycles = *(data + offset); + bootStatusReport.bootCycles = *(payloadStart + offset); nextReplyId = supv::EXE_REPORT; bootStatusReport.setValidity(true, true); @@ -1163,46 +1055,47 @@ ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data) ReturnValue_t PlocSupervisorHandler::handleLatchupStatusReport(const uint8_t* data) { ReturnValue_t result = returnvalue::OK; - result = verifyPacket(data, supv::SIZE_LATCHUP_STATUS_REPORT); + result = verifyPacket(data, tmReader.getFullPacketLen()); - if (result == SupvReturnValuesIF::CRC_FAILURE) { + if (result == result::CRC_FAILURE) { sif::error << "PlocSupervisorHandler::handleLatchupStatusReport: Latchup status report has " << "invalid crc" << std::endl; return result; } - uint16_t offset = supv::DATA_FIELD_OFFSET; - latchupStatusReport.id = *(data + offset); + const uint8_t* payloadData = tmReader.getPayloadStart(); + uint16_t offset = 0; + latchupStatusReport.id = *(payloadData + offset); offset += 1; - latchupStatusReport.cnt0 = *(data + offset) << 8 | *(data + offset + 1); + latchupStatusReport.cnt0 = *(payloadData + offset) << 8 | *(payloadData + offset + 1); offset += 2; - latchupStatusReport.cnt1 = *(data + offset) << 8 | *(data + offset + 1); + latchupStatusReport.cnt1 = *(payloadData + offset) << 8 | *(payloadData + offset + 1); offset += 2; - latchupStatusReport.cnt2 = *(data + offset) << 8 | *(data + offset + 1); + latchupStatusReport.cnt2 = *(payloadData + offset) << 8 | *(payloadData + offset + 1); offset += 2; - latchupStatusReport.cnt3 = *(data + offset) << 8 | *(data + offset + 1); + latchupStatusReport.cnt3 = *(payloadData + offset) << 8 | *(payloadData + offset + 1); offset += 2; - latchupStatusReport.cnt4 = *(data + offset) << 8 | *(data + offset + 1); + latchupStatusReport.cnt4 = *(payloadData + offset) << 8 | *(payloadData + offset + 1); offset += 2; - latchupStatusReport.cnt5 = *(data + offset) << 8 | *(data + offset + 1); + latchupStatusReport.cnt5 = *(payloadData + offset) << 8 | *(payloadData + offset + 1); offset += 2; - latchupStatusReport.cnt6 = *(data + offset) << 8 | *(data + offset + 1); + latchupStatusReport.cnt6 = *(payloadData + offset) << 8 | *(data + offset + 1); offset += 2; - uint16_t msec = *(data + offset) << 8 | *(data + offset + 1); + uint16_t msec = *(payloadData + offset) << 8 | *(payloadData + offset + 1); latchupStatusReport.isSet = msec >> supv::LatchupStatusReport::IS_SET_BIT_POS; latchupStatusReport.timeMsec = msec & (~(1 << latchupStatusReport.IS_SET_BIT_POS)); offset += 2; - latchupStatusReport.timeSec = *(data + offset); + latchupStatusReport.timeSec = *(payloadData + offset); offset += 1; - latchupStatusReport.timeMin = *(data + offset); + latchupStatusReport.timeMin = *(payloadData + offset); offset += 1; - latchupStatusReport.timeHour = *(data + offset); + latchupStatusReport.timeHour = *(payloadData + offset); offset += 1; - latchupStatusReport.timeDay = *(data + offset); + latchupStatusReport.timeDay = *(payloadData + offset); offset += 1; - latchupStatusReport.timeMon = *(data + offset); + latchupStatusReport.timeMon = *(payloadData + offset); offset += 1; - latchupStatusReport.timeYear = *(data + offset); + latchupStatusReport.timeYear = *(payloadData + offset); nextReplyId = supv::EXE_REPORT; @@ -1244,54 +1137,18 @@ ReturnValue_t PlocSupervisorHandler::handleLatchupStatusReport(const uint8_t* da return result; } -ReturnValue_t PlocSupervisorHandler::handleLoggingReport(const uint8_t* data) { - ReturnValue_t result = returnvalue::OK; - - result = verifyPacket(data, supv::SIZE_LOGGING_REPORT); - - if (result == SupvReturnValuesIF::CRC_FAILURE) { - sif::warning << "PlocSupervisorHandler::handleLoggingReport: Logging report has " - << "invalid crc" << std::endl; - return result; - } - - const uint8_t* dataField = data + supv::DATA_FIELD_OFFSET + sizeof(supv::RequestLoggingData::Sa); - result = loggingReport.read(); - if (result != returnvalue::OK) { - return result; - } - loggingReport.setValidityBufferGeneration(false); - size_t size = loggingReport.getSerializedSize(); - result = loggingReport.deSerialize(&dataField, &size, SerializeIF::Endianness::BIG); - if (result != returnvalue::OK) { - sif::warning << "PlocSupervisorHandler::handleLoggingReport: Deserialization failed" - << std::endl; - } - loggingReport.setValidityBufferGeneration(true); - loggingReport.setValidity(true, true); - result = loggingReport.commit(); - if (result != returnvalue::OK) { - return result; - } -#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_PLOC_SUPERVISOR == 1 - loggingReport.printSet(); -#endif - nextReplyId = supv::EXE_REPORT; - return result; -} - ReturnValue_t PlocSupervisorHandler::handleAdcReport(const uint8_t* data) { ReturnValue_t result = returnvalue::OK; result = verifyPacket(data, supv::SIZE_ADC_REPORT); - if (result == SupvReturnValuesIF::CRC_FAILURE) { + if (result == result::CRC_FAILURE) { sif::error << "PlocSupervisorHandler::handleAdcReport: ADC report has " << "invalid crc" << std::endl; return result; } - const uint8_t* dataField = data + supv::DATA_FIELD_OFFSET; + const uint8_t* dataField = data + supv::PAYLOAD_OFFSET; result = adcReport.read(); if (result != returnvalue::OK) { return result; @@ -1378,17 +1235,9 @@ size_t PlocSupervisorHandler::getNextReplyLength(DeviceCommandId_t commandId) { return replyLen; } -ReturnValue_t PlocSupervisorHandler::doSendReadHook() { - // Prevent DHB from polling UART during commands executed by the supervisor helper task - if (plocSupvHelperExecuting) { - return returnvalue::FAILED; - } - return returnvalue::OK; -} +void PlocSupervisorHandler::doOffActivity() {} -void PlocSupervisorHandler::doOffActivity() { startupState = StartupState::OFF; } - -void PlocSupervisorHandler::handleDeviceTM(const uint8_t* data, size_t dataSize, +void PlocSupervisorHandler::handleDeviceTm(const uint8_t* data, size_t dataSize, DeviceCommandId_t replyId) { ReturnValue_t result = returnvalue::OK; @@ -1414,8 +1263,8 @@ void PlocSupervisorHandler::handleDeviceTM(const uint8_t* data, size_t dataSize, } } -ReturnValue_t PlocSupervisorHandler::prepareEmptyCmd(uint16_t apid) { - supv::ApidOnlyPacket packet(spParams, apid); +ReturnValue_t PlocSupervisorHandler::prepareEmptyCmd(uint16_t apid, uint8_t serviceId) { + supv::NoPayloadPacket packet(spParams, apid, serviceId); ReturnValue_t result = packet.buildPacket(); if (result != returnvalue::OK) { return result; @@ -1427,7 +1276,7 @@ ReturnValue_t PlocSupervisorHandler::prepareEmptyCmd(uint16_t apid) { ReturnValue_t PlocSupervisorHandler::prepareSelBootImageCmd(const uint8_t* commandData) { supv::MPSoCBootSelect packet(spParams); ReturnValue_t result = - packet.buildPacket(*commandData, *(commandData + 1), *(commandData + 2), *(commandData + 3)); + packet.buildPacket(commandData[0], commandData[1], commandData[2], commandData[3]); if (result != returnvalue::OK) { return result; } @@ -1441,7 +1290,7 @@ ReturnValue_t PlocSupervisorHandler::prepareSetTimeRefCmd() { if (result != returnvalue::OK) { sif::warning << "PlocSupervisorHandler::prepareSetTimeRefCmd: Failed to get current time" << std::endl; - return SupvReturnValuesIF::GET_TIME_FAILURE; + return result::GET_TIME_FAILURE; } supv::SetTimeRef packet(spParams); result = packet.buildPacket(&time); @@ -1490,7 +1339,7 @@ ReturnValue_t PlocSupervisorHandler::prepareLatchupConfigCmd(const uint8_t* comm ReturnValue_t result = returnvalue::OK; uint8_t latchupId = *commandData; if (latchupId > 6) { - return SupvReturnValuesIF::INVALID_LATCHUP_ID; + return result::INVALID_LATCHUP_ID; } switch (deviceCommand) { case (supv::ENABLE_LATCHUP_ALERT): { @@ -1528,7 +1377,7 @@ ReturnValue_t PlocSupervisorHandler::prepareSetAlertLimitCmd(const uint8_t* comm uint32_t dutycycle = *(commandData + offset) << 24 | *(commandData + offset + 1) << 16 | *(commandData + offset + 2) << 8 | *(commandData + offset + 3); if (latchupId > 6) { - return SupvReturnValuesIF::INVALID_LATCHUP_ID; + return result::INVALID_LATCHUP_ID; } supv::SetAlertlimit packet(spParams); ReturnValue_t result = packet.buildPacket(latchupId, dutycycle); @@ -1579,7 +1428,7 @@ ReturnValue_t PlocSupervisorHandler::prepareSetAdcThresholdCmd(const uint8_t* co ReturnValue_t PlocSupervisorHandler::prepareRunAutoEmTest(const uint8_t* commandData) { uint8_t test = *commandData; if (test != 1 && test != 2) { - return SupvReturnValuesIF::INVALID_TEST_PARAM; + return result::INVALID_TEST_PARAM; } supv::RunAutoEmTests packet(spParams); ReturnValue_t result = packet.buildPacket(test); @@ -1590,48 +1439,6 @@ ReturnValue_t PlocSupervisorHandler::prepareRunAutoEmTest(const uint8_t* command return returnvalue::OK; } -ReturnValue_t PlocSupervisorHandler::prepareWipeMramCmd(const uint8_t* commandData) { - uint32_t start = 0; - uint32_t stop = 0; - size_t size = sizeof(start) + sizeof(stop); - SerializeAdapter::deSerialize(&start, &commandData, &size, SerializeIF::Endianness::BIG); - SerializeAdapter::deSerialize(&stop, &commandData, &size, SerializeIF::Endianness::BIG); - if ((stop - start) <= 0) { - return SupvReturnValuesIF::INVALID_MRAM_ADDRESSES; - } - supv::MramCmd packet(spParams); - ReturnValue_t result = packet.buildPacket(start, stop, supv::MramCmd::MramAction::WIPE); - if (result != returnvalue::OK) { - return result; - } - finishTcPrep(packet.getFullPacketLen()); - return returnvalue::OK; -} - -ReturnValue_t PlocSupervisorHandler::prepareDumpMramCmd(const uint8_t* commandData) { - uint32_t start = 0; - uint32_t stop = 0; - size_t size = sizeof(start) + sizeof(stop); - SerializeAdapter::deSerialize(&start, &commandData, &size, SerializeIF::Endianness::BIG); - SerializeAdapter::deSerialize(&stop, &commandData, &size, SerializeIF::Endianness::BIG); - if ((stop - start) <= 0) { - return SupvReturnValuesIF::INVALID_MRAM_ADDRESSES; - } - supv::MramCmd packet(spParams); - ReturnValue_t result = packet.buildPacket(start, stop, supv::MramCmd::MramAction::DUMP); - if (result != returnvalue::OK) { - return result; - } - expectedMramDumpPackets = (stop - start) / supv::MAX_DATA_CAPACITY; - if ((stop - start) % supv::MAX_DATA_CAPACITY) { - expectedMramDumpPackets++; - } - receivedMramDumpPackets = 0; - - finishTcPrep(packet.getFullPacketLen()); - return returnvalue::OK; -} - ReturnValue_t PlocSupervisorHandler::prepareSetGpioCmd(const uint8_t* commandData) { uint8_t port = *commandData; uint8_t pin = *(commandData + 1); @@ -1657,6 +1464,21 @@ ReturnValue_t PlocSupervisorHandler::prepareReadGpioCmd(const uint8_t* commandDa return returnvalue::OK; } +ReturnValue_t PlocSupervisorHandler::prepareFactoryResetCmd(const uint8_t* commandData, + size_t len) { + FactoryReset resetCmd(spParams); + std::optional op; + if (len > 0) { + op = commandData[0]; + } + ReturnValue_t result = resetCmd.buildPacket(op); + if (result != returnvalue::OK) { + return result; + } + finishTcPrep(resetCmd.getFullPacketLen()); + return returnvalue::OK; +} + void PlocSupervisorHandler::finishTcPrep(size_t packetLen) { nextReplyId = supv::ACK_REPORT; rawPacket = commandBuffer; @@ -1683,33 +1505,6 @@ ReturnValue_t PlocSupervisorHandler::prepareSetShutdownTimeoutCmd(const uint8_t* return returnvalue::OK; } -ReturnValue_t PlocSupervisorHandler::prepareLoggingRequest(const uint8_t* commandData, - size_t commandDataLen) { - using namespace supv; - RequestLoggingData::Sa sa = static_cast(*commandData); - uint8_t tpc = *(commandData + 1); - RequestLoggingData packet(spParams); - ReturnValue_t result = packet.buildPacket(sa, tpc); - if (result != returnvalue::OK) { - return result; - } - finishTcPrep(packet.getFullPacketLen()); - return returnvalue::OK; -} - -ReturnValue_t PlocSupervisorHandler::prepareEnableNvmsCommand(const uint8_t* commandData) { - using namespace supv; - uint8_t nvm01 = *(commandData); - uint8_t nvm3 = *(commandData + 1); - EnableNvms packet(spParams); - ReturnValue_t result = packet.buildPacket(nvm01, nvm3); - if (result != returnvalue::OK) { - return result; - } - finishTcPrep(packet.getFullPacketLen()); - return returnvalue::OK; -} - void PlocSupervisorHandler::disableAllReplies() { using namespace supv; DeviceReplyMap::iterator iter; @@ -1798,47 +1593,13 @@ void PlocSupervisorHandler::disableExeReportReply() { info->command->second.expectedReplies = 1; } -ReturnValue_t PlocSupervisorHandler::parseMramPackets(const uint8_t* packet, size_t remainingSize, - size_t* foundLen) { - ReturnValue_t result = IGNORE_FULL_PACKET; - uint16_t packetLen = 0; - *foundLen = 0; - - for (size_t idx = 0; idx < remainingSize; idx++) { - std::memcpy(spacePacketBuffer + bufferTop, packet + idx, 1); - bufferTop += 1; - *foundLen += 1; - if (bufferTop >= supv::SPACE_PACKET_HEADER_LENGTH) { - packetLen = readSpacePacketLength(spacePacketBuffer); - } - - if (bufferTop == supv::SPACE_PACKET_HEADER_LENGTH + packetLen + 1) { - packetInBuffer = true; - bufferTop = 0; - return checkMramPacketApid(); - } - - if (bufferTop == supv::MAX_PACKET_SIZE) { - *foundLen = remainingSize; - disableAllReplies(); - bufferTop = 0; - sif::info << "PlocSupervisorHandler::parseMramPackets: Can not find MRAM packet in space " - "packet buffer" - << std::endl; - return SupvReturnValuesIF::MRAM_PACKET_PARSING_FAILURE; - } - } - - return result; -} - ReturnValue_t PlocSupervisorHandler::handleMramDumpPacket(DeviceCommandId_t id) { ReturnValue_t result = returnvalue::FAILED; // Prepare packet for downlink if (packetInBuffer) { uint16_t packetLen = readSpacePacketLength(spacePacketBuffer); - result = verifyPacket(spacePacketBuffer, supv::SPACE_PACKET_HEADER_LENGTH + packetLen + 1); + result = verifyPacket(spacePacketBuffer, ccsds::HEADER_LEN + packetLen + 1); if (result != returnvalue::OK) { sif::warning << "PlocSupervisorHandler::handleMramDumpPacket: CRC failure" << std::endl; return result; @@ -1908,14 +1669,6 @@ void PlocSupervisorHandler::increaseExpectedMramReplies(DeviceCommandId_t id) { return; } -ReturnValue_t PlocSupervisorHandler::checkMramPacketApid() { - uint16_t apid = (spacePacketBuffer[0] << 8 | spacePacketBuffer[1]) & supv::APID_MASK; - if (apid != supv::APID_MRAM_DUMP_TM) { - return SupvReturnValuesIF::NO_MRAM_PACKET; - } - return APERIODIC_REPLY; -} - ReturnValue_t PlocSupervisorHandler::handleMramDumpFile(DeviceCommandId_t id) { #ifdef XIPHOS_Q7S if (not sdcMan->getActiveSdCard()) { @@ -1937,15 +1690,32 @@ ReturnValue_t PlocSupervisorHandler::handleMramDumpFile(DeviceCommandId_t id) { if (not std::filesystem::exists(activeMramFile)) { sif::warning << "PlocSupervisorHandler::handleMramDumpFile: MRAM file does not exist" << std::endl; - return SupvReturnValuesIF::MRAM_FILE_NOT_EXISTS; + return result::MRAM_FILE_NOT_EXISTS; } std::ofstream file(activeMramFile, std::ios_base::app | std::ios_base::out); - file.write(reinterpret_cast(spacePacketBuffer + supv::SPACE_PACKET_HEADER_LENGTH), - packetLen - 1); + file.write(reinterpret_cast(spacePacketBuffer + ccsds::HEADER_LEN), packetLen - 1); file.close(); return returnvalue::OK; } +ReturnValue_t PlocSupervisorHandler::prepareWipeMramCmd(const uint8_t* commandData) { + uint32_t start = 0; + uint32_t stop = 0; + size_t size = sizeof(start) + sizeof(stop); + SerializeAdapter::deSerialize(&start, &commandData, &size, SerializeIF::Endianness::BIG); + SerializeAdapter::deSerialize(&stop, &commandData, &size, SerializeIF::Endianness::BIG); + if ((stop - start) <= 0) { + return result::INVALID_MRAM_ADDRESSES; + } + supv::MramCmd packet(spParams); + ReturnValue_t result = packet.buildPacket(start, stop, supv::MramCmd::MramAction::WIPE); + if (result != returnvalue::OK) { + return result; + } + finishTcPrep(packet.getFullPacketLen()); + return returnvalue::OK; +} + uint16_t PlocSupervisorHandler::readSpacePacketLength(uint8_t* spacePacket) { return spacePacket[4] << 8 | spacePacket[5]; } @@ -1964,7 +1734,7 @@ ReturnValue_t PlocSupervisorHandler::createMramDumpFile() { std::string filename = "mram-dump--" + timeStamp + ".bin"; -#ifndef TE0720_1CFA +#ifdef XIPHOS_Q7S std::string currentMountPrefix = sdcMan->getCurrentMountPrefix(); #else std::string currentMountPrefix("/mnt/sd0"); @@ -1974,7 +1744,7 @@ ReturnValue_t PlocSupervisorHandler::createMramDumpFile() { if (not std::filesystem::exists(std::string(currentMountPrefix + "/" + supervisorFilePath))) { sif::warning << "PlocSupervisorHandler::createMramDumpFile: Supervisor path does not exist" << std::endl; - return SupvReturnValuesIF::PATH_DOES_NOT_EXIST; + return result::PATH_DOES_NOT_EXIST; } activeMramFile = currentMountPrefix + "/" + supervisorFilePath + "/" + filename; // Create new file @@ -1990,7 +1760,7 @@ ReturnValue_t PlocSupervisorHandler::getTimeStampString(std::string& timeStamp) if (result != returnvalue::OK) { sif::warning << "PlocSupervisorHandler::getTimeStampString: Failed to get current time" << std::endl; - return SupvReturnValuesIF::GET_TIME_FAILURE; + return result::GET_TIME_FAILURE; } timeStamp = std::to_string(time.year) + "-" + std::to_string(time.month) + "-" + std::to_string(time.day) + "--" + std::to_string(time.hour) + "-" + @@ -2005,7 +1775,7 @@ ReturnValue_t PlocSupervisorHandler::extractUpdateCommand(const uint8_t* command sizeof(params.startAddr) + sizeof(params.bytesWritten) + sizeof(params.seqCount) + sizeof(uint8_t)) { sif::warning << "PlocSupervisorHandler::extractUpdateCommand: Data size too big" << std::endl; - return SupvReturnValuesIF::INVALID_LENGTH; + return result::INVALID_LENGTH; } ReturnValue_t result = returnvalue::OK; result = extractBaseParams(&commandData, size, params); @@ -2054,7 +1824,7 @@ ReturnValue_t PlocSupervisorHandler::extractBaseParams(const uint8_t** commandDa params.file = std::string(reinterpret_cast(*commandData)); if (params.file.size() > (config::MAX_FILENAME_SIZE + config::MAX_PATH_SIZE)) { sif::warning << "PlocSupervisorHandler::extractUpdateCommand: Filename too long" << std::endl; - return SupvReturnValuesIF::FILENAME_TOO_LONG; + return result::FILENAME_TOO_LONG; } *commandData += params.file.size() + SIZE_NULL_TERMINATOR; remSize -= (params.file.size() + SIZE_NULL_TERMINATOR); @@ -2085,9 +1855,9 @@ ReturnValue_t PlocSupervisorHandler::eventSubscription() { if (result != returnvalue::OK) { return result; } - result = manager->subscribeToEventRange(eventQueue->getId(), - event::getEventId(PlocSupvHelper::SUPV_UPDATE_FAILED), - event::getEventId(PlocSupvHelper::SUPV_MEM_CHECK_FAIL)); + result = manager->subscribeToEventRange( + eventQueue->getId(), event::getEventId(PlocSupvUartManager::SUPV_UPDATE_FAILED), + event::getEventId(PlocSupvUartManager::SUPV_MEM_CHECK_FAIL)); if (result != returnvalue::OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "PlocSupervisorHandler::eventSubscritpion: Failed to subscribe to events from " @@ -2099,19 +1869,13 @@ ReturnValue_t PlocSupervisorHandler::eventSubscription() { return result; } -ReturnValue_t PlocSupervisorHandler::handleExecutionSuccessReport(const uint8_t* data) { +ReturnValue_t PlocSupervisorHandler::handleExecutionSuccessReport(ExecutionReport& report) { DeviceCommandId_t commandId = getPendingCommand(); + ReturnValue_t result = OK; switch (commandId) { case supv::READ_GPIO: { - supv::ExecutionReport exe(data, supv::SIZE_EXE_REPORT); - if (exe.isNull()) { - return returnvalue::FAILED; - } - ReturnValue_t result = exe.checkSize(); - if (result != returnvalue::OK) { - return result; - } - uint16_t gpioState = exe.getStatusCode(); + // TODO: Fix + uint16_t gpioState = report.getStatusCode(); #if OBSW_DEBUG_PLOC_SUPERVISOR == 1 sif::info << "PlocSupervisorHandler: Read GPIO TM, State: " << gpioState << std::endl; #endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ @@ -2144,26 +1908,184 @@ ReturnValue_t PlocSupervisorHandler::handleExecutionSuccessReport(const uint8_t* return returnvalue::OK; } -void PlocSupervisorHandler::handleExecutionFailureReport(uint16_t statusCode) { +void PlocSupervisorHandler::handleExecutionFailureReport(ExecutionReport& report) { using namespace supv; DeviceCommandId_t commandId = getPendingCommand(); + report.printStatusInformation(); if (commandId != DeviceHandlerIF::NO_COMMAND_ID) { - triggerEvent(SUPV_EXE_FAILURE, commandId, static_cast(statusCode)); + triggerEvent(SUPV_EXE_FAILURE, commandId, static_cast(report.getStatusCode())); } - sendFailureReport(EXE_REPORT, SupvReturnValuesIF::RECEIVED_EXE_FAILURE); + sendFailureReport(EXE_REPORT, result::RECEIVED_EXE_FAILURE); disableExeReportReply(); } +void PlocSupervisorHandler::handleBadApidServiceCombination(Event event, unsigned int apid, + unsigned int serviceId) { + const char* printString = ""; + if (event == SUPV_UNKNOWN_TM) { + printString = "PlocSupervisorHandler: Unknown"; + } else if (event == SUPV_UNINIMPLEMENTED_TM) { + printString = "PlocSupervisorHandler: Unimplemented"; + } + triggerEvent(event, apid, tmReader.getServiceId()); + sif::warning << printString << " APID service combination 0x" << std::setw(2) << std::setfill('0') + << std::hex << apid << ", 0x" << std::setw(2) << serviceId << std::endl; +} + void PlocSupervisorHandler::printAckFailureInfo(uint16_t statusCode, DeviceCommandId_t commandId) { - sif::warning << "PlocSupervisorHandler: Received Ack failure report with status code: 0x" - << std::hex << statusCode << std::endl; switch (commandId) { case (supv::SET_TIME_REF): { - sif::info << "PlocSupervisoHandler: Setting time failed. Make sure the OBC has a valid time" - << std::endl; + sif::warning + << "PlocSupervisoHandler: Setting time failed. Make sure the OBC has a valid time" + << std::endl; break; } default: break; } } + +ReturnValue_t PlocSupervisorHandler::getSwitches(const uint8_t** switches, + uint8_t* numberOfSwitches) { + if (powerSwitch == power::NO_SWITCH) { + return DeviceHandlerBase::NO_SWITCH; + } + *numberOfSwitches = 1; + *switches = &powerSwitch; + return returnvalue::OK; +} + +uint32_t PlocSupervisorHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { + return 7000; +} + +// ReturnValue_t PlocSupervisorHandler::checkMramPacketApid() { +// uint16_t apid = (spacePacketBuffer[0] << 8 | spacePacketBuffer[1]) & supv::APID_MASK; +// TODO: Fix +// if (apid != supv::APID_MRAM_DUMP_TM) { +// return result::NO_MRAM_PACKET; +// } +// return APERIODIC_REPLY; +//} + +// ReturnValue_t PlocSupervisorHandler::parseMramPackets(const uint8_t* packet, size_t +// remainingSize, +// size_t* foundLen) { +// ReturnValue_t result = IGNORE_FULL_PACKET; +// uint16_t packetLen = 0; +// *foundLen = 0; +// +// for (size_t idx = 0; idx < remainingSize; idx++) { +// std::memcpy(spacePacketBuffer + bufferTop, packet + idx, 1); +// bufferTop += 1; +// *foundLen += 1; +// if (bufferTop >= ccsds::HEADER_LEN) { +// packetLen = readSpacePacketLength(spacePacketBuffer); +// } +// +// if (bufferTop == ccsds::HEADER_LEN + packetLen + 1) { +// packetInBuffer = true; +// bufferTop = 0; +// return checkMramPacketApid(); +// } +// +// if (bufferTop == supv::MAX_PACKET_SIZE) { +// *foundLen = remainingSize; +// disableAllReplies(); +// bufferTop = 0; +// sif::info << "PlocSupervisorHandler::parseMramPackets: Can not find MRAM packet in space " +// "packet buffer" +// << std::endl; +// return result::MRAM_PACKET_PARSING_FAILURE; +// } +// } +// +// return result; +// } + +// ReturnValue_t PlocSupervisorHandler::prepareDumpMramCmd(const uint8_t* commandData) { +// uint32_t start = 0; +// uint32_t stop = 0; +// size_t size = sizeof(start) + sizeof(stop); +// SerializeAdapter::deSerialize(&start, &commandData, &size, SerializeIF::Endianness::BIG); +// SerializeAdapter::deSerialize(&stop, &commandData, &size, SerializeIF::Endianness::BIG); +// if ((stop - start) <= 0) { +// return SupvReturnValuesIF::INVALID_MRAM_ADDRESSES; +// } +// supv::MramCmd packet(spParams); +// ReturnValue_t result = packet.buildPacket(start, stop, supv::MramCmd::MramAction::DUMP); +// if (result != returnvalue::OK) { +// return result; +// } +// expectedMramDumpPackets = (stop - start) / supv::MAX_DATA_CAPACITY; +// if ((stop - start) % supv::MAX_DATA_CAPACITY) { +// expectedMramDumpPackets++; +// } +// receivedMramDumpPackets = 0; +// +// finishTcPrep(packet.getFullPacketLen()); +// return returnvalue::OK; +// } + +// ReturnValue_t PlocSupervisorHandler::prepareLoggingRequest(const uint8_t* commandData, +// size_t commandDataLen) { +// using namespace supv; +// RequestLoggingData::Sa sa = static_cast(*commandData); +// uint8_t tpc = *(commandData + 1); +// RequestLoggingData packet(spParams); +// ReturnValue_t result = packet.buildPacket(sa, tpc); +// if (result != returnvalue::OK) { +// return result; +// } +// finishTcPrep(packet.getFullPacketLen()); +// return returnvalue::OK; +// } + +// ReturnValue_t PlocSupervisorHandler::prepareEnableNvmsCommand(const uint8_t* commandData) { +// using namespace supv; +// uint8_t nvm01 = *(commandData); +// uint8_t nvm3 = *(commandData + 1); +// EnableNvms packet(spParams); +// ReturnValue_t result = packet.buildPacket(nvm01, nvm3); +// if (result != returnvalue::OK) { +// return result; +// } +// finishTcPrep(packet.getFullPacketLen()); +// return returnvalue::OK; +// } + +// ReturnValue_t PlocSupervisorHandler::handleLoggingReport(const uint8_t* data) { +// ReturnValue_t result = returnvalue::OK; +// +// result = verifyPacket(data, supv::SIZE_LOGGING_REPORT); +// +// if (result == SupvReturnValuesIF::CRC_FAILURE) { +// sif::warning << "PlocSupervisorHandler::handleLoggingReport: Logging report has " +// << "invalid crc" << std::endl; +// return result; +// } +// +// const uint8_t* dataField = data + supv::PAYLOAD_OFFSET + sizeof(supv::RequestLoggingData::Sa); +// result = loggingReport.read(); +// if (result != returnvalue::OK) { +// return result; +// } +// loggingReport.setValidityBufferGeneration(false); +// size_t size = loggingReport.getSerializedSize(); +// result = loggingReport.deSerialize(&dataField, &size, SerializeIF::Endianness::BIG); +// if (result != returnvalue::OK) { +// sif::warning << "PlocSupervisorHandler::handleLoggingReport: Deserialization failed" +// << std::endl; +// } +// loggingReport.setValidityBufferGeneration(true); +// loggingReport.setValidity(true, true); +// result = loggingReport.commit(); +// if (result != returnvalue::OK) { +// return result; +// } +//#if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_PLOC_SUPERVISOR == 1 +// loggingReport.printSet(); +//#endif +// nextReplyId = supv::EXE_REPORT; +// return result; +// } diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 65c23fa6..4ffe4166 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -1,9 +1,9 @@ #ifndef MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_ #define MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_ +#include + #include "OBSWConfig.h" -#include "PlocSupvHelper.h" -#include "bsp_q7s/fs/SdCardManager.h" #include "devices/powerSwitcherList.h" #include "fsfw/devicehandlers/DeviceHandlerBase.h" #include "fsfw/timemanager/Countdown.h" @@ -11,7 +11,12 @@ #include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" #include "fsfw_hal/linux/serial/SerialComIF.h" #include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" -#include "linux/devices/devicedefinitions/SupvReturnValuesIF.h" + +#ifdef XIPHOS_Q7S +#include "bsp_q7s/fs/SdCardManager.h" +#endif + +using supv::ExecutionReport; /** * @brief This is the device handler for the supervisor of the PLOC which is programmed by @@ -27,9 +32,8 @@ */ class PlocSupervisorHandler : public DeviceHandlerBase { public: - PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie, - Gpio uartIsolatorSwitch, power::Switch_t powerSwitch, - PlocSupvHelper* supvHelper); + PlocSupervisorHandler(object_id_t objectId, CookieIF* comCookie, Gpio uartIsolatorSwitch, + power::Switch_t powerSwitch, PlocSupvUartManager& supvHelper); virtual ~PlocSupervisorHandler(); virtual ReturnValue_t initialize() override; @@ -48,7 +52,6 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId, size_t* foundLen) override; ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) override; - void setNormalDatapoolEntriesInvalid() override; uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) override; @@ -56,7 +59,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { uint8_t expectedReplies = 1, bool useAlternateId = false, DeviceCommandId_t alternateReplyID = 0) override; size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override; - ReturnValue_t doSendReadHook() override; + // ReturnValue_t doSendReadHook() override; void doOffActivity() override; private: @@ -64,18 +67,21 @@ class PlocSupervisorHandler : public DeviceHandlerBase { //! [EXPORT] : [COMMENT] PLOC supervisor crc failure in telemetry packet static const Event SUPV_MEMORY_READ_RPT_CRC_FAILURE = MAKE_EVENT(1, severity::LOW); + //! [EXPORT] : [COMMENT] Unhandled event. P1: APID, P2: Service ID + static constexpr Event SUPV_UNKNOWN_TM = MAKE_EVENT(2, severity::LOW); + static constexpr Event SUPV_UNINIMPLEMENTED_TM = MAKE_EVENT(3, severity::LOW); //! [EXPORT] : [COMMENT] PLOC supervisor received acknowledgment failure report - static const Event SUPV_ACK_FAILURE = MAKE_EVENT(2, severity::LOW); + static const Event SUPV_ACK_FAILURE = MAKE_EVENT(4, severity::LOW); //! [EXPORT] : [COMMENT] PLOC received execution failure report //! P1: ID of command for which the execution failed //! P2: Status code sent by the supervisor handler - static const Event SUPV_EXE_FAILURE = MAKE_EVENT(3, severity::LOW); + static const Event SUPV_EXE_FAILURE = MAKE_EVENT(5, severity::LOW); //! [EXPORT] : [COMMENT] PLOC supervisor reply has invalid crc - static const Event SUPV_CRC_FAILURE_EVENT = MAKE_EVENT(4, severity::LOW); + static const Event SUPV_CRC_FAILURE_EVENT = MAKE_EVENT(6, severity::LOW); //! [EXPORT] : [COMMENT] Supervisor helper currently executing a command - static const Event SUPV_HELPER_EXECUTING = MAKE_EVENT(5, severity::LOW); + static const Event SUPV_HELPER_EXECUTING = MAKE_EVENT(7, severity::LOW); //! [EXPORT] : [COMMENT] Failed to build the command to shutdown the MPSoC - static const Event SUPV_MPSOC_SHUWDOWN_BUILD_FAILED = MAKE_EVENT(5, severity::LOW); + static const Event SUPV_MPSOC_SHUTDOWN_BUILD_FAILED = MAKE_EVENT(8, severity::LOW); static const uint16_t APID_MASK = 0x7FF; static const uint16_t PACKET_SEQUENCE_COUNT_MASK = 0x3FFF; @@ -101,7 +107,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]; SpacePacketCreator creator; - ploc::SpTcParams spParams = ploc::SpTcParams(creator); + supv::TcParams spParams = supv::TcParams(creator); /** * This variable is used to store the id of the next reply to receive. This is necessary @@ -113,6 +119,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { SerialComIF* uartComIf = nullptr; LinuxLibgpioIF* gpioComIF = nullptr; Gpio uartIsolatorSwitch; + bool shutdownCmdSent = false; supv::HkSet hkset; supv::BootStatusReport bootStatusReport; @@ -121,8 +128,9 @@ class PlocSupervisorHandler : public DeviceHandlerBase { supv::AdcReport adcReport; const power::Switch_t powerSwitch = power::NO_SWITCH; + supv::TmBase tmReader; - PlocSupvHelper* supvHelper = nullptr; + PlocSupvUartManager& uartManager; MessageQueueIF* eventQueue = nullptr; /** Number of expected replies following the MRAM dump command */ @@ -136,17 +144,14 @@ class PlocSupervisorHandler : public DeviceHandlerBase { /** This buffer is used to concatenate space packets received in two different read steps */ uint8_t spacePacketBuffer[supv::MAX_PACKET_SIZE]; -#ifndef TE0720_1CFA +#ifdef XIPHOS_Q7S SdCardManager* sdcMan = nullptr; -#endif /* BOARD_TE0720 == 0 */ +#endif // Path to supervisor specific files on SD card std::string supervisorFilePath = "ploc/supervisor"; std::string activeMramFile; - // Supervisor helper class currently executing a command - bool plocSupvHelperExecuting = false; - Countdown executionReportTimeout = Countdown(EXECUTION_DEFAULT_TIMEOUT, false); Countdown acknowledgementReportTimeout = Countdown(ACKNOWLEDGE_DEFAULT_TIMEOUT, false); // Vorago nees some time to boot properly @@ -210,7 +215,8 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t handleBootStatusReport(const uint8_t* data); ReturnValue_t handleLatchupStatusReport(const uint8_t* data); - ReturnValue_t handleLoggingReport(const uint8_t* data); + void handleBadApidServiceCombination(Event result, unsigned int apid, unsigned int serviceId); + // ReturnValue_t handleLoggingReport(const uint8_t* data); ReturnValue_t handleAdcReport(const uint8_t* data); /** @@ -229,13 +235,13 @@ class PlocSupervisorHandler : public DeviceHandlerBase { * @param dataSize Size of telemetry in bytes. * @param replyId Id of the reply. This will be added to the ActionMessage. */ - void handleDeviceTM(const uint8_t* data, size_t dataSize, DeviceCommandId_t replyId); + void handleDeviceTm(const uint8_t* data, size_t dataSize, DeviceCommandId_t replyId); /** * @brief This function prepares a space packet which does not transport any data in the * packet data field apart from the crc. */ - ReturnValue_t prepareEmptyCmd(uint16_t apid); + ReturnValue_t prepareEmptyCmd(uint16_t apid, uint8_t serviceId); /** * @brief This function initializes the space packet to select the boot image of the MPSoC. @@ -258,6 +264,8 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t prepareRestartTriesCmd(const uint8_t* commandData); + ReturnValue_t prepareFactoryResetCmd(const uint8_t* commandData, size_t len); + /** * @brief This function fills the command buffer with the packet to enable or disable the * watchdogs on the PLOC. @@ -278,11 +286,11 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t prepareSetAdcThresholdCmd(const uint8_t* commandData); ReturnValue_t prepareRunAutoEmTest(const uint8_t* commandData); ReturnValue_t prepareWipeMramCmd(const uint8_t* commandData); - ReturnValue_t prepareDumpMramCmd(const uint8_t* commandData); + // ReturnValue_t prepareDumpMramCmd(const uint8_t* commandData); ReturnValue_t prepareSetGpioCmd(const uint8_t* commandData); ReturnValue_t prepareReadGpioCmd(const uint8_t* commandData); - ReturnValue_t prepareLoggingRequest(const uint8_t* commandData, size_t commandDataLen); - ReturnValue_t prepareEnableNvmsCommand(const uint8_t* commandData); + // ReturnValue_t prepareLoggingRequest(const uint8_t* commandData, size_t commandDataLen); + // ReturnValue_t prepareEnableNvmsCommand(const uint8_t* commandData); /** * @brief Copies the content of a space packet to the command buffer. @@ -317,7 +325,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { * @brief Function is called in scanForReply and fills the spacePacketBuffer with the read * data until a full packet has been received. */ - ReturnValue_t parseMramPackets(const uint8_t* packet, size_t remainingSize, size_t* foundlen); + // ReturnValue_t parseMramPackets(const uint8_t* packet, size_t remainingSize, size_t* foundlen); /** * @brief This function generates the Service 8 packets for the MRAM dump data. @@ -335,7 +343,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { * @brief Function checks if the packet written to the space packet buffer is really a * MRAM dump packet. */ - ReturnValue_t checkMramPacketApid(); + // ReturnValue_t checkMramPacketApid(); /** * @brief Writes the data of the MRAM dump to a file. The file will be created when receiving @@ -373,8 +381,8 @@ class PlocSupervisorHandler : public DeviceHandlerBase { supv::UpdateParams& params); ReturnValue_t eventSubscription(); - ReturnValue_t handleExecutionSuccessReport(const uint8_t* data); - void handleExecutionFailureReport(uint16_t statusCode); + ReturnValue_t handleExecutionSuccessReport(ExecutionReport& report); + void handleExecutionFailureReport(ExecutionReport& report); void printAckFailureInfo(uint16_t statusCode, DeviceCommandId_t commandId); }; diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp deleted file mode 100644 index 5f34cb21..00000000 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ /dev/null @@ -1,803 +0,0 @@ -#include "PlocSupvHelper.h" - -#include -#include - -#include -#include -#include - -#include "OBSWConfig.h" -#ifdef XIPHOS_Q7S -#include "bsp_q7s/fs/FilesystemHelper.h" -#include "bsp_q7s/fs/SdCardManager.h" -#endif - -#include "fsfw/tasks/TaskFactory.h" -#include "fsfw/timemanager/Countdown.h" -#include "mission/utility/Filenaming.h" -#include "mission/utility/ProgressPrinter.h" -#include "mission/utility/Timestamp.h" - -PlocSupvHelper::PlocSupvHelper(object_id_t objectId) : SystemObject(objectId) { - spParams.maxSize = sizeof(commandBuffer); - resetSpParams(); -} - -PlocSupvHelper::~PlocSupvHelper() {} - -ReturnValue_t PlocSupvHelper::initialize() { -#ifdef XIPHOS_Q7S - sdcMan = SdCardManager::instance(); - if (sdcMan == nullptr) { - sif::warning << "PlocSupvHelper::initialize: Invalid SD Card Manager" << std::endl; - return returnvalue::FAILED; - } -#endif - return returnvalue::OK; -} - -ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { - ReturnValue_t result = returnvalue::OK; - semaphore.acquire(); - while (true) { - switch (internalState) { - case InternalState::IDLE: { - semaphore.acquire(); - break; - } - case InternalState::UPDATE: { - result = executeUpdate(); - if (result == returnvalue::OK) { - triggerEvent(SUPV_UPDATE_SUCCESSFUL, result); - } else if (result == PROCESS_TERMINATED) { - // Event already triggered - } else { - triggerEvent(SUPV_UPDATE_FAILED, result); - } - internalState = InternalState::IDLE; - break; - } - case InternalState::CHECK_MEMORY: { - executeFullCheckMemoryCommand(); - internalState = InternalState::IDLE; - break; - } - case InternalState::CONTINUE_UPDATE: { - result = continueUpdate(); - if (result == returnvalue::OK) { - triggerEvent(SUPV_CONTINUE_UPDATE_SUCCESSFUL, result); - } else if (result == PROCESS_TERMINATED) { - // Event already triggered - } else { - triggerEvent(SUPV_CONTINUE_UPDATE_FAILED, result); - } - internalState = InternalState::IDLE; - break; - } - case InternalState::REQUEST_EVENT_BUFFER: { - result = performEventBufferRequest(); - if (result == returnvalue::OK) { - triggerEvent(SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL, result); - } else if (result == PROCESS_TERMINATED) { - // Event already triggered - break; - } else { - triggerEvent(SUPV_EVENT_BUFFER_REQUEST_FAILED, result); - } - internalState = InternalState::IDLE; - break; - } - default: - sif::debug << "PlocSupvHelper::performOperation: Invalid state" << std::endl; - break; - } - } -} - -ReturnValue_t PlocSupvHelper::setComIF(SerialComIF* uartComIF_) { - if (uartComIF_ == nullptr) { - sif::warning << "PlocSupvHelper::initialize: Provided invalid uart com if" << std::endl; - return returnvalue::FAILED; - } - uartComIF = uartComIF_; - return returnvalue::OK; -} - -void PlocSupvHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; } - -ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId, - uint32_t startAddress) { - supv::UpdateParams params; - params.file = file; - params.memId = memoryId; - params.startAddr = startAddress; - params.bytesWritten = 0; - params.seqCount = 1; - params.deleteMemory = true; - return performUpdate(params); -} - -ReturnValue_t PlocSupvHelper::performUpdate(const supv::UpdateParams& params) { - ReturnValue_t result = returnvalue::OK; -#ifdef XIPHOS_Q7S - result = FilesystemHelper::checkPath(params.file); - if (result != returnvalue::OK) { - sif::warning << "PlocSupvHelper::startUpdate: File " << params.file << " does not exist" - << std::endl; - return result; - } - result = FilesystemHelper::fileExists(params.file); - if (result != returnvalue::OK) { - sif::warning << "PlocSupvHelper::startUpdate: The file " << params.file << " does not exist" - << std::endl; - return result; - } -#endif -#ifdef TE0720_1CFA - if (not std::filesystem::exists(file)) { - sif::warning << "PlocSupvHelper::startUpdate: The file " << file << " does not exist" - << std::endl; - return returnvalue::FAILED; - } -#endif - update.file = params.file; - update.fullFileSize = getFileSize(update.file); - if (params.bytesWritten > update.fullFileSize) { - sif::warning << "Invalid start bytes counter " << params.bytesWritten - << ", smaller than full file length" << update.fullFileSize << std::endl; - return returnvalue::FAILED; - } - update.length = update.fullFileSize - params.bytesWritten; - update.memoryId = params.memId; - update.startAddress = params.startAddr; - update.progressPercent = 0; - update.bytesWritten = params.bytesWritten; - update.crcShouldBeChecked = true; - update.packetNum = 1; - update.deleteMemory = params.deleteMemory; - update.sequenceCount = params.seqCount; - internalState = InternalState::UPDATE; - uartComIF->flushUartTxAndRxBuf(comCookie); - semaphore.release(); - return result; -} - -ReturnValue_t PlocSupvHelper::performMemCheck(std::string file, uint8_t memoryId, - uint32_t startAddress) { - update.file = file; - update.fullFileSize = getFileSize(file); - return performMemCheck(memoryId, startAddress, getFileSize(update.file), true); -} - -ReturnValue_t PlocSupvHelper::performMemCheck(uint8_t memoryId, uint32_t startAddress, - size_t sizeToCheck, bool checkCrc) { - update.memoryId = memoryId; - update.startAddress = startAddress; - update.length = sizeToCheck; - update.crcShouldBeChecked = checkCrc; - internalState = InternalState::CHECK_MEMORY; - uartComIF->flushUartTxAndRxBuf(comCookie); - semaphore.release(); - return returnvalue::OK; -} - -void PlocSupvHelper::initiateUpdateContinuation() { - internalState = InternalState::CONTINUE_UPDATE; - semaphore.release(); -} - -ReturnValue_t PlocSupvHelper::startEventbBufferRequest(std::string path) { -#ifdef XIPHOS_Q7S - ReturnValue_t result = FilesystemHelper::checkPath(path); - if (result != returnvalue::OK) { - return result; - } -#endif - if (not std::filesystem::exists(path)) { - return PATH_NOT_EXISTS; - } - eventBufferReq.path = path; - internalState = InternalState::REQUEST_EVENT_BUFFER; - uartComIF->flushUartTxAndRxBuf(comCookie); - semaphore.release(); - return returnvalue::OK; -} - -void PlocSupvHelper::stopProcess() { terminate = true; } - -void PlocSupvHelper::executeFullCheckMemoryCommand() { - ReturnValue_t result; - if (update.crcShouldBeChecked) { - sif::info << "PLOC SUPV Mem Check: Calculating Image CRC" << std::endl; - result = calcImageCrc(); - if (result != returnvalue::OK) { - triggerEvent(SUPV_MEM_CHECK_FAIL, result); - return; - } - } - sif::info << "PLOC SUPV Mem Check: Selecting Memory" << std::endl; - result = selectMemory(); - if (result != returnvalue::OK) { - triggerEvent(SUPV_MEM_CHECK_FAIL, result); - return; - } - sif::info << "PLOC SUPV Mem Check: Preparing Update" << std::endl; - result = prepareUpdate(); - if (result != returnvalue::OK) { - triggerEvent(SUPV_MEM_CHECK_FAIL, result); - return; - } - sif::info << "PLOC SUPV Mem Check: Memory Check" << std::endl; - result = handleCheckMemoryCommand(); - if (result == returnvalue::OK) { - triggerEvent(SUPV_MEM_CHECK_OK, result); - } else { - triggerEvent(SUPV_MEM_CHECK_FAIL, result); - } -} - -ReturnValue_t PlocSupvHelper::executeUpdate() { - ReturnValue_t result = returnvalue::OK; - sif::info << "PLOC SUPV Update MPSoC: Calculating Image CRC" << std::endl; - result = calcImageCrc(); - if (result != returnvalue::OK) { - return result; - } - sif::info << "PLOC SUPV Update MPSoC: Selecting Memory" << std::endl; - result = selectMemory(); - if (result != returnvalue::OK) { - return result; - } - sif::info << "PLOC SUPV Update MPSoC: Preparing Update" << std::endl; - result = prepareUpdate(); - if (result != returnvalue::OK) { - return result; - } - if (update.deleteMemory) { - sif::info << "PLOC SUPV Update MPSoC: Erasing Memory" << std::endl; - result = eraseMemory(); - if (result != returnvalue::OK) { - return result; - } - } - return updateOperation(); -} - -ReturnValue_t PlocSupvHelper::continueUpdate() { - ReturnValue_t result = prepareUpdate(); - if (result != returnvalue::OK) { - return result; - } - return updateOperation(); -} - -ReturnValue_t PlocSupvHelper::updateOperation() { - sif::info << "PlocSupvHelper::performUpdate: Writing Update Packets" << std::endl; - auto result = writeUpdatePackets(); - if (result != returnvalue::OK) { - return result; - } - sif::info << "PlocSupvHelper::performUpdate: Memory Check" << std::endl; - return handleCheckMemoryCommand(); -} - -ReturnValue_t PlocSupvHelper::writeUpdatePackets() { - ReturnValue_t result = returnvalue::OK; -#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 - ProgressPrinter progressPrinter("Supervisor update", update.fullFileSize, - ProgressPrinter::HALF_PERCENT); -#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ - uint8_t tempData[supv::WriteMemory::CHUNK_MAX + 1]{}; - std::ifstream file(update.file, std::ifstream::binary); - uint16_t dataLength = 0; - ccsds::SequenceFlags seqFlags; - while (update.bytesWritten < update.fullFileSize) { - if (terminate) { - terminate = false; - triggerEvent(TERMINATED_UPDATE_PROCEDURE); - return PROCESS_TERMINATED; - } - size_t remainingSize = update.fullFileSize - update.bytesWritten; - bool lastSegment = false; - if (remainingSize > supv::WriteMemory::CHUNK_MAX) { - dataLength = supv::WriteMemory::CHUNK_MAX; - } else { - lastSegment = true; - dataLength = static_cast(remainingSize); - } - if (file.is_open()) { - file.seekg(update.bytesWritten, std::ios::beg); - file.read(reinterpret_cast(tempData), dataLength); - if (!file) { - sif::warning << "PlocSupvHelper::performUpdate: Read only " << file.gcount() << " of " - << dataLength << " bytes" << std::endl; - sif::info << "PlocSupvHelper::performUpdate: Failed when trying to read byte " - << update.bytesWritten << std::endl; - } - } else { - return FILE_CLOSED_ACCIDENTALLY; - } - if (update.bytesWritten == 0) { - seqFlags = ccsds::SequenceFlags::FIRST_SEGMENT; - } else if (lastSegment) { - seqFlags = ccsds::SequenceFlags::LAST_SEGMENT; - } else { - seqFlags = ccsds::SequenceFlags::CONTINUATION; - } - resetSpParams(); - float progress = static_cast(update.bytesWritten) / update.fullFileSize; - uint8_t progPercent = std::floor(progress * 100); - if (progPercent > update.progressPercent) { - update.progressPercent = progPercent; - if (progPercent % 5 == 0) { - // Useful to allow restarting the update - triggerEvent(SUPV_UPDATE_PROGRESS, buildProgParams1(progPercent, update.sequenceCount), - update.bytesWritten); - } - } - supv::WriteMemory packet(spParams); - result = packet.buildPacket(seqFlags, update.sequenceCount, update.memoryId, - update.startAddress + update.bytesWritten, dataLength, tempData); - if (result != returnvalue::OK) { - triggerEvent(WRITE_MEMORY_FAILED, buildProgParams1(progPercent, update.sequenceCount), - update.bytesWritten); - return result; - } - result = handlePacketTransmission(packet); - if (result != returnvalue::OK) { - triggerEvent(WRITE_MEMORY_FAILED, buildProgParams1(progPercent, update.sequenceCount), - update.bytesWritten); - return result; - } - update.sequenceCount++; - update.packetNum += 1; - update.bytesWritten += dataLength; - -#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 - progressPrinter.print(update.bytesWritten); -#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ - } - return result; -} - -uint32_t PlocSupvHelper::buildProgParams1(uint8_t percent, uint16_t seqCount) { - return (static_cast(percent) << 24) | static_cast(seqCount); -} - -ReturnValue_t PlocSupvHelper::performEventBufferRequest() { - using namespace supv; - ReturnValue_t result = returnvalue::OK; - resetSpParams(); - RequestLoggingData packet(spParams); - result = packet.buildPacket(RequestLoggingData::Sa::REQUEST_EVENT_BUFFERS); - if (result != returnvalue::OK) { - return result; - } - result = sendCommand(packet); - if (result != returnvalue::OK) { - return result; - } - result = handleAck(); - if (result != returnvalue::OK) { - return result; - } - result = - handleTmReception(ccsds::HEADER_LEN, tmBuf.data(), supv::recv_timeout::UPDATE_STATUS_REPORT); - if (result != returnvalue::OK) { - return result; - } - ploc::SpTmReader spReader(tmBuf.data(), tmBuf.size()); - bool exeAlreadyReceived = false; - if (spReader.getApid() == supv::APID_EXE_FAILURE) { - exeAlreadyReceived = true; - result = handleRemainingExeReport(spReader); - } else if (spReader.getApid() == supv::APID_MRAM_DUMP_TM) { - result = handleEventBufferReception(spReader); - } - - if (not exeAlreadyReceived) { - result = handleExe(); - if (result != returnvalue::OK) { - return result; - } - } - return result; -} - -ReturnValue_t PlocSupvHelper::handleRemainingExeReport(ploc::SpTmReader& reader) { - size_t remBytes = reader.getPacketDataLen() + 1; - ReturnValue_t result = handleTmReception(remBytes, tmBuf.data() + ccsds::HEADER_LEN); - if (result != returnvalue::OK) { - sif::warning << "Reading exe failure report failed" << std::endl; - } - result = exeReportHandling(); - if (result != returnvalue::OK) { - sif::warning << "Handling exe report failed" << std::endl; - } - return result; -} - -ReturnValue_t PlocSupvHelper::selectMemory() { - ReturnValue_t result = returnvalue::OK; - resetSpParams(); - supv::MPSoCBootSelect packet(spParams); - result = packet.buildPacket(update.memoryId); - if (result != returnvalue::OK) { - return result; - } - result = handlePacketTransmission(packet); - if (result != returnvalue::OK) { - return result; - } - return returnvalue::OK; -} - -ReturnValue_t PlocSupvHelper::prepareUpdate() { - ReturnValue_t result = returnvalue::OK; - resetSpParams(); - supv::ApidOnlyPacket packet(spParams, supv::APID_PREPARE_UPDATE); - result = packet.buildPacket(); - if (result != returnvalue::OK) { - return result; - } - result = handlePacketTransmission(packet, PREPARE_UPDATE_EXECUTION_REPORT); - if (result != returnvalue::OK) { - return result; - } - return returnvalue::OK; -} - -ReturnValue_t PlocSupvHelper::eraseMemory() { - ReturnValue_t result = returnvalue::OK; - resetSpParams(); - supv::EraseMemory eraseMemory(spParams); - result = eraseMemory.buildPacket(update.memoryId, update.startAddress + update.bytesWritten, - update.length); - if (result != returnvalue::OK) { - return result; - } - result = handlePacketTransmission(eraseMemory, supv::recv_timeout::ERASE_MEMORY); - if (result != returnvalue::OK) { - return result; - } - return returnvalue::OK; -} - -ReturnValue_t PlocSupvHelper::handlePacketTransmission(ploc::SpTcBase& packet, - uint32_t timeoutExecutionReport) { - ReturnValue_t result = returnvalue::OK; - result = sendCommand(packet); - if (result != returnvalue::OK) { - return result; - } - result = handleAck(); - if (result != returnvalue::OK) { - return result; - } - result = handleExe(timeoutExecutionReport); - if (result != returnvalue::OK) { - return result; - } - return returnvalue::OK; -} - -ReturnValue_t PlocSupvHelper::sendCommand(ploc::SpTcBase& packet) { - ReturnValue_t result = returnvalue::OK; - rememberApid = packet.getApid(); - result = uartComIF->sendMessage(comCookie, packet.getFullPacket(), packet.getFullPacketLen()); - if (result != returnvalue::OK) { - sif::warning << "PlocSupvHelper::sendCommand: Failed to send command" << std::endl; - triggerEvent(SUPV_SENDING_COMMAND_FAILED, result, static_cast(internalState)); - return result; - } - return result; -} - -ReturnValue_t PlocSupvHelper::handleAck() { - ReturnValue_t result = returnvalue::OK; - - result = handleTmReception(supv::SIZE_ACK_REPORT); - if (result != returnvalue::OK) { - triggerEvent(ACK_RECEPTION_FAILURE, result, static_cast(rememberApid)); - sif::warning << "PlocSupvHelper::handleAck: Error in reception of acknowledgment report" - << std::endl; - return result; - } - supv::AcknowledgmentReport ackReport(tmBuf.data(), tmBuf.size()); - result = checkReceivedTm(ackReport); - if (result != returnvalue::OK) { - return result; - } - result = ackReport.checkApid(); - if (result != returnvalue::OK) { - if (result == SupvReturnValuesIF::RECEIVED_ACK_FAILURE) { - triggerEvent(SUPV_ACK_FAILURE_REPORT, static_cast(ackReport.getRefApid())); - } else if (result == SupvReturnValuesIF::INVALID_APID) { - triggerEvent(SUPV_ACK_INVALID_APID, static_cast(rememberApid)); - } - return result; - } - return returnvalue::OK; -} - -ReturnValue_t PlocSupvHelper::handleExe(uint32_t timeout) { - ReturnValue_t result = returnvalue::OK; - - result = handleTmReception(supv::SIZE_EXE_REPORT, tmBuf.data(), timeout); - if (result != returnvalue::OK) { - triggerEvent(EXE_RECEPTION_FAILURE, result, static_cast(rememberApid)); - sif::warning << "PlocSupvHelper::handleExe: Error in reception of execution report" - << std::endl; - return result; - } - - return exeReportHandling(); -} - -ReturnValue_t PlocSupvHelper::exeReportHandling() { - supv::ExecutionReport exeReport(tmBuf.data(), tmBuf.size()); - - ReturnValue_t result = checkReceivedTm(exeReport); - if (result != returnvalue::OK) { - return result; - } - result = exeReport.checkApid(); - if (result != returnvalue::OK) { - if (result == SupvReturnValuesIF::RECEIVED_EXE_FAILURE) { - triggerEvent(SUPV_EXE_FAILURE_REPORT, static_cast(exeReport.getRefApid())); - } else if (result == SupvReturnValuesIF::INVALID_APID) { - triggerEvent(SUPV_EXE_INVALID_APID, static_cast(rememberApid)); - } - return result; - } - return result; -} - -ReturnValue_t PlocSupvHelper::handleTmReception(size_t remainingBytes, uint8_t* readBuf, - uint32_t timeout) { - ReturnValue_t result = returnvalue::OK; - size_t readBytes = 0; - size_t currentBytes = 0; - Countdown countdown(timeout); - if (readBuf == nullptr) { - readBuf = tmBuf.data(); - } - while (!countdown.hasTimedOut()) { - result = receive(readBuf + readBytes, ¤tBytes, remainingBytes); - if (result != returnvalue::OK) { - return result; - } - readBytes += currentBytes; - remainingBytes = remainingBytes - currentBytes; - if (remainingBytes == 0) { - break; - } - } - if (remainingBytes != 0) { - sif::warning << "PlocSupvHelper::handleTmReception: Failed to read " << std::dec - << remainingBytes << " remaining bytes" << std::endl; - return returnvalue::FAILED; - } - return result; -} - -ReturnValue_t PlocSupvHelper::checkReceivedTm(ploc::SpTmReader& reader) { - ReturnValue_t result = reader.checkSize(); - if (result != returnvalue::OK) { - triggerEvent(SUPV_REPLY_SIZE_MISSMATCH, rememberApid); - return result; - } - result = reader.checkCrc(); - if (result != returnvalue::OK) { - triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); - return result; - } - return result; -} - -ReturnValue_t PlocSupvHelper::receive(uint8_t* data, size_t* readBytes, size_t requestBytes) { - ReturnValue_t result = returnvalue::OK; - uint8_t* buffer = nullptr; - result = uartComIF->requestReceiveMessage(comCookie, requestBytes); - if (result != returnvalue::OK) { - sif::warning << "PlocSupvHelper::receive: Failed to request reply" << std::endl; - triggerEvent(SUPV_HELPER_REQUESTING_REPLY_FAILED, result, - static_cast(static_cast(internalState))); - return returnvalue::FAILED; - } - result = uartComIF->readReceivedMessage(comCookie, &buffer, readBytes); - if (result != returnvalue::OK) { - sif::warning << "PlocSupvHelper::receive: Failed to read received message" << std::endl; - triggerEvent(SUPV_HELPER_READING_REPLY_FAILED, result, static_cast(internalState)); - return returnvalue::FAILED; - } - if (*readBytes > 0) { - std::memcpy(data, buffer, *readBytes); - } else { - TaskFactory::delayTask(40); - } - return result; -} - -ReturnValue_t PlocSupvHelper::calcImageCrc() { - ReturnValue_t result = returnvalue::OK; - if (update.fullFileSize == 0) { - return returnvalue::FAILED; - } -#ifdef XIPHOS_Q7S - result = FilesystemHelper::checkPath(update.file); - if (result != returnvalue::OK) { - sif::warning << "PlocSupvHelper::calcImageCrc: File " << update.file << " does not exist" - << std::endl; - return result; - } -#endif - - auto crc16Calcer = etl::crc16_ccitt(); - std::ifstream file(update.file, std::ifstream::binary); - std::array crcBuf{}; -#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 - ProgressPrinter progress("Supervisor update crc calculation", update.fullFileSize, - ProgressPrinter::ONE_PERCENT); -#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ - uint32_t byteCount = 0; - size_t bytesToRead = 1024; - while (byteCount < update.fullFileSize) { - size_t remLen = update.fullFileSize - byteCount; - if (remLen < 1024) { - bytesToRead = remLen; - } else { - bytesToRead = 1024; - } - file.seekg(byteCount, file.beg); - file.read(reinterpret_cast(crcBuf.data()), bytesToRead); - crc16Calcer.add(crcBuf.begin(), crcBuf.begin() + bytesToRead); - -#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 - progress.print(byteCount); -#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ - byteCount += bytesToRead; - } -#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 - progress.print(byteCount); -#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ - update.crc = crc16Calcer.value(); - return result; -} - -ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { - ReturnValue_t result = returnvalue::OK; - resetSpParams(); - // Will hold status report for later processing - std::array statusReportBuf{}; - supv::UpdateStatusReport updateStatusReport(tmBuf.data(), tmBuf.size()); - // Verification of update write procedure - supv::CheckMemory packet(spParams); - result = packet.buildPacket(update.memoryId, update.startAddress, update.fullFileSize); - if (result != returnvalue::OK) { - return result; - } - result = sendCommand(packet); - if (result != returnvalue::OK) { - return result; - } - result = handleAck(); - if (result != returnvalue::OK) { - return result; - } - - bool exeAlreadyHandled = false; - uint32_t timeout = std::max(CRC_EXECUTION_TIMEOUT, supv::recv_timeout::UPDATE_STATUS_REPORT); - result = handleTmReception(ccsds::HEADER_LEN, tmBuf.data(), timeout); - ploc::SpTmReader spReader(tmBuf.data(), tmBuf.size()); - if (spReader.getApid() == supv::APID_EXE_FAILURE) { - exeAlreadyHandled = true; - result = handleRemainingExeReport(spReader); - } else if (spReader.getApid() == supv::APID_UPDATE_STATUS_REPORT) { - size_t remBytes = spReader.getPacketDataLen() + 1; - result = handleTmReception(remBytes, tmBuf.data() + ccsds::HEADER_LEN, - supv::recv_timeout::UPDATE_STATUS_REPORT); - if (result != returnvalue::OK) { - sif::warning - << "PlocSupvHelper::handleCheckMemoryCommand: Failed to receive update status report" - << std::endl; - return result; - } - result = updateStatusReport.checkCrc(); - if (result != returnvalue::OK) { - sif::warning << "PlocSupvHelper::handleCheckMemoryCommand: CRC check failed" << std::endl; - return result; - } - // Copy into other buffer because data will be overwritten when reading execution report - std::memcpy(statusReportBuf.data(), tmBuf.data(), updateStatusReport.getNominalSize()); - } - - if (not exeAlreadyHandled) { - result = handleExe(CRC_EXECUTION_TIMEOUT); - if (result != returnvalue::OK) { - return result; - } - } - - // Now process the status report - updateStatusReport.setData(statusReportBuf.data(), statusReportBuf.size()); - result = updateStatusReport.parseDataField(); - if (result != returnvalue::OK) { - return result; - } - if (update.crcShouldBeChecked) { - result = updateStatusReport.verifycrc(update.crc); - if (result != returnvalue::OK) { - sif::warning << "PlocSupvHelper::handleCheckMemoryCommand: CRC failure. Expected CRC 0x" - << std::setfill('0') << std::hex << std::setw(4) - << static_cast(update.crc) << " but received CRC 0x" << std::setw(4) - << updateStatusReport.getCrc() << std::dec << std::endl; - return result; - } - } - return result; -} - -uint32_t PlocSupvHelper::getFileSize(std::string filename) { - std::ifstream file(filename, std::ifstream::binary); - file.seekg(0, file.end); - uint32_t size = file.tellg(); - file.close(); - return size; -} - -ReturnValue_t PlocSupvHelper::handleEventBufferReception(ploc::SpTmReader& reader) { - ReturnValue_t result = returnvalue::OK; -#ifdef XIPHOS_Q7S - if (not sdcMan->getActiveSdCard()) { - return HasFileSystemIF::FILESYSTEM_INACTIVE; - } -#endif - std::string filename = Filenaming::generateAbsoluteFilename( - eventBufferReq.path, eventBufferReq.filename, timestamping); - std::ofstream file(filename, std::ios_base::app | std::ios_base::out); - uint32_t packetsRead = 0; - size_t requestLen = 0; - bool firstPacket = true; - for (packetsRead = 0; packetsRead < NUM_EVENT_BUFFER_PACKETS; packetsRead++) { - if (terminate) { - triggerEvent(SUPV_EVENT_BUFFER_REQUEST_TERMINATED, packetsRead - 1); - file.close(); - return PROCESS_TERMINATED; - } - if (packetsRead == NUM_EVENT_BUFFER_PACKETS - 1) { - requestLen = SIZE_EVENT_BUFFER_LAST_PACKET; - } else { - requestLen = SIZE_EVENT_BUFFER_FULL_PACKET; - } - if (firstPacket) { - firstPacket = false; - requestLen -= 6; - } - result = handleTmReception(requestLen); - if (result != returnvalue::OK) { - sif::debug << "PlocSupvHelper::handleEventBufferReception: Failed while trying to read packet" - << " " << packetsRead + 1 << std::endl; - file.close(); - return result; - } - ReturnValue_t result = reader.checkCrc(); - if (result != returnvalue::OK) { - triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); - return result; - } - uint16_t apid = reader.getApid(); - if (apid != supv::APID_MRAM_DUMP_TM) { - sif::warning << "PlocSupvHelper::handleEventBufferReception: Did not expect space packet " - << "with APID 0x" << std::hex << apid << std::endl; - file.close(); - return EVENT_BUFFER_REPLY_INVALID_APID; - } - file.write(reinterpret_cast(reader.getPacketData()), - reader.getPayloadDataLength()); - } - return result; -} - -void PlocSupvHelper::resetSpParams() { spParams.buf = commandBuffer; } diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp new file mode 100644 index 00000000..ee232f47 --- /dev/null +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -0,0 +1,1157 @@ +#include +#include // Contains file controls like O_RDWR +#include +#include +#include +#include +#include + +#include +#include +#include + +#include "OBSWConfig.h" +#include "tas/hdlc.h" +#ifdef XIPHOS_Q7S +#include "bsp_q7s/fs/FilesystemHelper.h" +#include "bsp_q7s/fs/SdCardManager.h" +#endif + +#include + +#include "fsfw/tasks/TaskFactory.h" +#include "fsfw/timemanager/Countdown.h" +#include "mission/utility/Filenaming.h" +#include "mission/utility/ProgressPrinter.h" +#include "mission/utility/Timestamp.h" + +using namespace returnvalue; +using namespace supv; + +PlocSupvUartManager::PlocSupvUartManager(object_id_t objectId) + : SystemObject(objectId), + recRingBuf(4096, true), + decodedRingBuf(1200 * MAX_STORED_DECODED_PACKETS, true), + ipcRingBuf(1200 * MAX_STORED_DECODED_PACKETS, true) { + resetSpParams(); + spParams.maxSize = cmdBuf.size(); + semaphore = SemaphoreFactory::instance()->createBinarySemaphore(); + semaphore->acquire(); + lock = MutexFactory::instance()->createMutex(); + ipcLock = MutexFactory::instance()->createMutex(); +} + +PlocSupvUartManager::~PlocSupvUartManager() = default; + +ReturnValue_t PlocSupvUartManager::initializeInterface(CookieIF* cookie) { + auto* uartCookie = dynamic_cast(cookie); + if (uartCookie == nullptr) { + return FAILED; + } + std::string devname = uartCookie->getDeviceFile(); + /* Get file descriptor */ + serialPort = open(devname.c_str(), O_RDWR); + if (serialPort < 0) { + sif::warning << "PlocSupvUartManager::initializeInterface: open call failed with error [" + << errno << ", " << strerror(errno) << std::endl; + return FAILED; + } + // 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); + tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control + uart::enableRead(tty); + uart::ignoreCtrlLines(tty); + + // Use non-canonical mode and clear echo flag + tty.c_lflag &= ~(ICANON | ECHO); + + // Blocking mode, 0.2 seconds timeout + tty.c_cc[VTIME] = 2; + tty.c_cc[VMIN] = 0; + + uart::setBaudrate(tty, uartCookie->getBaudrate()); + if (tcsetattr(serialPort, TCSANOW, &tty) != 0) { + sif::warning << "PlocSupvUartManager::initializeInterface: tcsetattr call failed with error [" + << errno << ", " << strerror(errno) << std::endl; + } + // Flush received and unread data + tcflush(serialPort, TCIOFLUSH); + return OK; +} + +ReturnValue_t PlocSupvUartManager::initialize() { +#ifdef XIPHOS_Q7S + sdcMan = SdCardManager::instance(); + if (sdcMan == nullptr) { + sif::warning << "PlocSupvHelper::initialize: Invalid SD Card Manager" << std::endl; + return returnvalue::FAILED; + } +#endif + return returnvalue::OK; +} + +ReturnValue_t PlocSupvUartManager::performOperation(uint8_t operationCode) { + bool putTaskToSleep = false; + while (true) { + lock->lockMutex(); + state = InternalState::SLEEPING; + lock->unlockMutex(); + semaphore->acquire(); + while (true) { + if (putTaskToSleep) { + performUartShutdown(); + break; + } + handleUartReception(); + lock->lockMutex(); + InternalState currentState = state; + lock->unlockMutex(); + switch (currentState) { + case InternalState::SLEEPING: + case InternalState::GO_TO_SLEEP: { + putTaskToSleep = true; + break; + } + case InternalState::DEDICATED_REQUEST: { + updateVtime(1); + handleRunningLongerRequest(); + updateVtime(2); + MutexGuard mg(lock); + state = InternalState::DEFAULT; + break; + } + case InternalState::DEFAULT: { + break; + } + } + } + } +} + +ReturnValue_t PlocSupvUartManager::handleUartReception() { + ReturnValue_t result = OK; + ReturnValue_t status = OK; + ssize_t bytesRead = read(serialPort, reinterpret_cast(recBuf.data()), + static_cast(recBuf.size())); + if (bytesRead == 0) { + while (result != NO_PACKET_FOUND) { + result = tryHdlcParsing(); + if (result != NO_PACKET_FOUND and result != OK) { + status = result; + } + } + } else if (bytesRead < 0) { + sif::warning << "PlocSupvHelper::performOperation: read call failed with error [" << errno + << ", " << strerror(errno) << "]" << std::endl; + return FAILED; + } else if (bytesRead >= static_cast(recBuf.size())) { + sif::error << "PlocSupvHelper::performOperation: Receive buffer too small for " << bytesRead + << " bytes" << std::endl; + return FAILED; + } else if (bytesRead > 0) { + if (debugMode) { + sif::info << "Received " << bytesRead << " bytes from the PLOC Supervisor:" << std::endl; + arrayprinter::print(recBuf.data(), bytesRead); + } + recRingBuf.writeData(recBuf.data(), bytesRead); + status = tryHdlcParsing(); + } + return status; +} + +ReturnValue_t PlocSupvUartManager::startUpdate(std::string file, uint8_t memoryId, + uint32_t startAddress) { + supv::UpdateParams params; + params.file = file; + params.memId = memoryId; + params.startAddr = startAddress; + params.bytesWritten = 0; + params.seqCount = 1; + params.deleteMemory = true; + return performUpdate(params); +} + +ReturnValue_t PlocSupvUartManager::performUpdate(const supv::UpdateParams& params) { + lock->lockMutex(); + InternalState current = state; + lock->unlockMutex(); + if (current != InternalState::DEFAULT) { + return HasActionsIF::IS_BUSY; + } + ReturnValue_t result = returnvalue::OK; +#ifdef XIPHOS_Q7S + result = FilesystemHelper::checkPath(params.file); + if (result != returnvalue::OK) { + sif::warning << "PlocSupvHelper::startUpdate: File " << params.file << " does not exist" + << std::endl; + return result; + } + result = FilesystemHelper::fileExists(params.file); + if (result != returnvalue::OK) { + sif::warning << "PlocSupvHelper::startUpdate: The file " << params.file << " does not exist" + << std::endl; + return result; + } +#endif +#ifdef TE0720_1CFA + if (not std::filesystem::exists(file)) { + sif::warning << "PlocSupvHelper::startUpdate: The file " << file << " does not exist" + << std::endl; + return returnvalue::FAILED; + } +#endif + { + MutexGuard mg(lock); + + update.file = params.file; + update.fullFileSize = getFileSize(update.file); + if (params.bytesWritten > update.fullFileSize) { + sif::warning << "Invalid start bytes counter " << params.bytesWritten + << ", smaller than full file length" << update.fullFileSize << std::endl; + return returnvalue::FAILED; + } + update.length = update.fullFileSize - params.bytesWritten; + update.memoryId = params.memId; + update.startAddress = params.startAddr; + update.progressPercent = 0; + update.bytesWritten = params.bytesWritten; + update.crcShouldBeChecked = true; + update.packetNum = 1; + update.deleteMemory = params.deleteMemory; + update.sequenceCount = params.seqCount; + state = InternalState::DEDICATED_REQUEST; + request = Request::UPDATE; + } + return result; +} + +ReturnValue_t PlocSupvUartManager::performMemCheck(std::string file, uint8_t memoryId, + uint32_t startAddress) { + lock->lockMutex(); + InternalState current = state; + lock->unlockMutex(); + if (current != InternalState::DEFAULT) { + return HasActionsIF::IS_BUSY; + } + return performMemCheck(file, memoryId, startAddress, getFileSize(update.file), true); +} + +ReturnValue_t PlocSupvUartManager::performMemCheck(std::string file, uint8_t memoryId, + uint32_t startAddress, size_t sizeToCheck, + bool checkCrc) { + { + MutexGuard mg(lock); + update.file = file; + update.fullFileSize = getFileSize(file); + state = InternalState::DEDICATED_REQUEST; + request = Request::CHECK_MEMORY; + update.memoryId = memoryId; + update.startAddress = startAddress; + update.length = sizeToCheck; + update.crcShouldBeChecked = checkCrc; + } + return returnvalue::OK; +} + +ReturnValue_t PlocSupvUartManager::initiateUpdateContinuation() { + lock->lockMutex(); + InternalState current = state; + lock->unlockMutex(); + if (current != InternalState::DEFAULT) { + return HasActionsIF::IS_BUSY; + } + MutexGuard mg(lock); + state = InternalState::DEDICATED_REQUEST; + request = Request::CONTINUE_UPDATE; + return returnvalue::OK; +} + +// ReturnValue_t PlocSupvHelper::startEventBufferRequest(std::string path) { +//#ifdef XIPHOS_Q7S +// ReturnValue_t result = FilesystemHelper::checkPath(path); +// if (result != returnvalue::OK) { +// return result; +// } +//#endif +// if (not std::filesystem::exists(path)) { +// return PATH_NOT_EXISTS; +// } +// eventBufferReq.path = path; +// request = Request::REQUEST_EVENT_BUFFER; +// //uartComIF->flushUartTxAndRxBuf(comCookie); +// semaphore->release(); +// return returnvalue::OK; +// } + +void PlocSupvUartManager::stop() { + MutexGuard mg(lock); + if (state == InternalState::SLEEPING or state == InternalState::GO_TO_SLEEP) { + return; + } + state = InternalState::GO_TO_SLEEP; +} + +void PlocSupvUartManager::start() { + MutexGuard mg(lock); + if (state != InternalState::SLEEPING and state != InternalState::GO_TO_SLEEP) { + return; + } + state = InternalState::DEFAULT; + semaphore->release(); +} + +void PlocSupvUartManager::executeFullCheckMemoryCommand() { + ReturnValue_t result; + if (update.crcShouldBeChecked) { + sif::info << "PLOC SUPV Mem Check: Calculating Image CRC" << std::endl; + result = calcImageCrc(); + if (result != returnvalue::OK) { + triggerEvent(SUPV_MEM_CHECK_FAIL, result); + return; + } + } + sif::info << "PLOC SUPV Mem Check: Selecting Memory" << std::endl; + result = selectMemory(); + if (result != returnvalue::OK) { + triggerEvent(SUPV_MEM_CHECK_FAIL, result, 1); + return; + } + sif::info << "PLOC SUPV Mem Check: Preparing Update" << std::endl; + result = prepareUpdate(); + if (result != returnvalue::OK) { + triggerEvent(SUPV_MEM_CHECK_FAIL, result, 2); + return; + } + sif::info << "PLOC SUPV Mem Check: Memory Check" << std::endl; + handleCheckMemoryCommand(3); +} + +ReturnValue_t PlocSupvUartManager::executeUpdate() { + ReturnValue_t result = returnvalue::OK; + sif::info << "PLOC SUPV Update MPSoC: Calculating Image CRC" << std::endl; + result = calcImageCrc(); + if (result != returnvalue::OK) { + return result; + } + sif::info << "PLOC SUPV Update MPSoC: Selecting Memory" << std::endl; + result = selectMemory(); + if (result != returnvalue::OK) { + return result; + } + sif::info << "PLOC SUPV Update MPSoC: Preparing Update" << std::endl; + result = prepareUpdate(); + if (result != returnvalue::OK) { + return result; + } + if (update.deleteMemory) { + sif::info << "PLOC SUPV Update MPSoC: Erasing Memory" << std::endl; + result = eraseMemory(); + if (result != returnvalue::OK) { + return result; + } + } + return updateOperation(); +} + +ReturnValue_t PlocSupvUartManager::continueUpdate() { + ReturnValue_t result = prepareUpdate(); + if (result != returnvalue::OK) { + return result; + } + return updateOperation(); +} + +ReturnValue_t PlocSupvUartManager::updateOperation() { + sif::info << "PlocSupvHelper::performUpdate: Writing Update Packets" << std::endl; + auto result = writeUpdatePackets(); + if (result != returnvalue::OK) { + return result; + } + sif::info << "PlocSupvHelper::performUpdate: Memory Check" << std::endl; + return handleCheckMemoryCommand(0); +} + +ReturnValue_t PlocSupvUartManager::writeUpdatePackets() { + ReturnValue_t result = returnvalue::OK; +#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 + ProgressPrinter progressPrinter("Supervisor update", update.fullFileSize, + ProgressPrinter::HALF_PERCENT); +#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + uint8_t tempData[supv::WriteMemory::CHUNK_MAX + 1]{}; + if (not std::filesystem::exists(update.file)) { + sif::error << "PlocSupvUartManager::writeUpdatePackets: File " << update.file + << " does not exist" << std::endl; + return HasFileSystemIF::FILE_DOES_NOT_EXIST; + } + std::ifstream file(update.file, std::ifstream::binary); + uint16_t dataLength = 0; + ccsds::SequenceFlags seqFlags; + while (update.bytesWritten < update.fullFileSize) { + size_t remainingSize = update.fullFileSize - update.bytesWritten; + bool lastSegment = false; + if (remainingSize > supv::WriteMemory::CHUNK_MAX) { + dataLength = supv::WriteMemory::CHUNK_MAX; + } else { + lastSegment = true; + dataLength = static_cast(remainingSize); + } + if (file.is_open()) { + file.seekg(update.bytesWritten, std::ios::beg); + file.read(reinterpret_cast(tempData), dataLength); + if (!file) { + sif::warning << "PlocSupvHelper::performUpdate: Read only " << file.gcount() << " of " + << dataLength << " bytes" << std::endl; + sif::info << "PlocSupvHelper::performUpdate: Failed when trying to read byte " + << update.bytesWritten << std::endl; + } + } else { + return FILE_CLOSED_ACCIDENTALLY; + } + if (update.bytesWritten == 0) { + seqFlags = ccsds::SequenceFlags::FIRST_SEGMENT; + } else if (lastSegment) { + seqFlags = ccsds::SequenceFlags::LAST_SEGMENT; + } else { + seqFlags = ccsds::SequenceFlags::CONTINUATION; + } + resetSpParams(); + float progress = static_cast(update.bytesWritten) / update.fullFileSize; + uint8_t progPercent = std::floor(progress * 100); + if (progPercent > update.progressPercent) { + update.progressPercent = progPercent; + if (progPercent % 5 == 0) { + // Useful to allow restarting the update + triggerEvent(SUPV_UPDATE_PROGRESS, buildProgParams1(progPercent, update.sequenceCount), + update.bytesWritten); + } + } + supv::WriteMemory packet(spParams); + result = packet.buildPacket(seqFlags, update.sequenceCount, update.memoryId, + update.startAddress + update.bytesWritten, dataLength, tempData); + if (result != returnvalue::OK) { + triggerEvent(WRITE_MEMORY_FAILED, buildProgParams1(progPercent, update.sequenceCount), + update.bytesWritten); + return result; + } + result = handlePacketTransmissionNoReply(packet, 5000); + if (result != returnvalue::OK) { + triggerEvent(WRITE_MEMORY_FAILED, buildProgParams1(progPercent, update.sequenceCount), + update.bytesWritten); + return result; + } + + update.sequenceCount++; + update.packetNum += 1; + update.bytesWritten += dataLength; + +#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 + progressPrinter.print(update.bytesWritten); +#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + // TaskFactory::delayTask(1); + } + return result; +} + +uint32_t PlocSupvUartManager::buildProgParams1(uint8_t percent, uint16_t seqCount) { + return (static_cast(percent) << 24) | static_cast(seqCount); +} + +// ReturnValue_t PlocSupvHelper::performEventBufferRequest() { +// using namespace supv; +// ReturnValue_t result = returnvalue::OK; +// resetSpParams(); +// RequestLoggingData packet(spParams); +// result = packet.buildPacket(RequestLoggingData::Sa::REQUEST_EVENT_BUFFERS); +// if (result != returnvalue::OK) { +// return result; +// } +// result = sendCommand(packet); +// if (result != returnvalue::OK) { +// return result; +// } +// result = handleAck(); +// if (result != returnvalue::OK) { +// return result; +// } +// result = +// handleTmReception(ccsds::HEADER_LEN, tmBuf.data(), +// supv::recv_timeout::UPDATE_STATUS_REPORT); +// if (result != returnvalue::OK) { +// return result; +// } +// ploc::SpTmReader spReader(tmBuf.data(), tmBuf.size()); +// bool exeAlreadyReceived = false; +// if (spReader.getApid() == supv::APID_EXE_FAILURE) { +// exeAlreadyReceived = true; +// result = handleRemainingExeReport(spReader); +// } else if (spReader.getApid() == supv::APID_MRAM_DUMP_TM) { +// result = handleEventBufferReception(spReader); +// } +// +// if (not exeAlreadyReceived) { +// result = handleExe(); +// if (result != returnvalue::OK) { +// return result; +// } +// } +// return result; +// } + +ReturnValue_t PlocSupvUartManager::selectMemory() { + ReturnValue_t result = returnvalue::OK; + resetSpParams(); + supv::MPSoCBootSelect packet(spParams); + result = packet.buildPacket(update.memoryId); + if (result != returnvalue::OK) { + return result; + } + result = handlePacketTransmissionNoReply(packet, 2000); + if (result != returnvalue::OK) { + return result; + } + return returnvalue::OK; +} + +ReturnValue_t PlocSupvUartManager::prepareUpdate() { + ReturnValue_t result = returnvalue::OK; + resetSpParams(); + supv::NoPayloadPacket packet(spParams, Apid::BOOT_MAN, + static_cast(tc::BootManId::PREPARE_UPDATE)); + result = packet.buildPacket(); + if (result != returnvalue::OK) { + return result; + } + result = handlePacketTransmissionNoReply(packet, PREPARE_UPDATE_EXECUTION_REPORT); + if (result != returnvalue::OK) { + return result; + } + return returnvalue::OK; +} + +ReturnValue_t PlocSupvUartManager::eraseMemory() { + ReturnValue_t result = returnvalue::OK; + resetSpParams(); + supv::EraseMemory eraseMemory(spParams); + result = eraseMemory.buildPacket(update.memoryId, update.startAddress + update.bytesWritten, + update.length); + if (result != returnvalue::OK) { + return result; + } + result = handlePacketTransmissionNoReply(eraseMemory, supv::timeout::ERASE_MEMORY); + if (result != returnvalue::OK) { + return result; + } + return returnvalue::OK; +} + +ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( + supv::TcBase& packet, uint32_t timeoutExecutionReport) { + ReturnValue_t result = returnvalue::OK; + result = encodeAndSendPacket(packet.getFullPacket(), packet.getFullPacketLen()); + if (result != returnvalue::OK) { + return result; + } + Countdown countdown(timeoutExecutionReport); + dur_millis_t currentDelay = 5; + bool ackReceived = false; + bool packetWasHandled = false; + while (true) { + handleUartReception(); + if (not decodedQueue.empty()) { + size_t packetLen = 0; + decodedQueue.retrieve(&packetLen); + decodedRingBuf.readData(decodedBuf.data(), packetLen, true); + tmReader.setData(decodedBuf.data(), packetLen); + result = checkReceivedTm(); + if (result != returnvalue::OK) { + continue; + } + if (tmReader.getModuleApid() == Apid::TMTC_MAN) { + int retval = 0; + if (not ackReceived) { + retval = handleAckReception(packet, packetLen); + if (retval == 1) { + ackReceived = true; + packetWasHandled = true; + } else if (retval == -1) { + return returnvalue::FAILED; + } + } else { + retval = handleExeAckReception(packet, packetLen); + if (retval == 1) { + break; + } else if (retval == -1) { + return returnvalue::FAILED; + } + } + } + if (not packetWasHandled) { + pushIpcData(decodedBuf.data(), packetLen); + decodedRingBuf.deleteData(packetLen); + } + } else { + TaskFactory::delayTask(currentDelay); + if (currentDelay < 80) { + currentDelay *= 2; + } + } + if (countdown.hasTimedOut()) { + return result::NO_REPLY_TIMEOUT; + } + } + return returnvalue::OK; +} + +int PlocSupvUartManager::handleAckReception(supv::TcBase& tc, size_t packetLen) { + uint8_t serviceId = tmReader.getServiceId(); + if (serviceId == static_cast(supv::tm::TmtcId::ACK) or + serviceId == static_cast(supv::tm::TmtcId::NAK)) { + AcknowledgmentReport ackReport(tmReader); + ReturnValue_t result = ackReport.parse(); + if (result != returnvalue::OK) { + triggerEvent(ACK_RECEPTION_FAILURE); + return -1; + } + if (ackReport.getRefModuleApid() == tc.getModuleApid() and + ackReport.getRefServiceId() == tc.getServiceId()) { + if (serviceId == static_cast(supv::tm::TmtcId::ACK)) { + return 1; + } else if (serviceId == static_cast(supv::tm::TmtcId::NAK)) { + ackReport.printStatusInformation(); + triggerEvent( + SUPV_ACK_FAILURE_REPORT, + buildApidServiceParam1(ackReport.getRefModuleApid(), ackReport.getRefServiceId()), + ackReport.getStatusCode()); + return -1; + } + // Should never happen + return -1; + } else { + pushIpcData(decodedBuf.data(), packetLen); + decodedRingBuf.deleteData(packetLen); + } + } + return 0; +} + +int PlocSupvUartManager::handleExeAckReception(supv::TcBase& tc, size_t packetLen) { + uint8_t serviceId = tmReader.getServiceId(); + if (serviceId == static_cast(supv::tm::TmtcId::EXEC_ACK) or + serviceId == static_cast(supv::tm::TmtcId::EXEC_NAK)) { + ExecutionReport exeReport(tmReader); + ReturnValue_t result = exeReport.parse(); + if (result != returnvalue::OK) { + triggerEvent(EXE_RECEPTION_FAILURE); + return -1; + } + if (exeReport.getRefModuleApid() == tc.getModuleApid() and + exeReport.getRefServiceId() == tc.getServiceId()) { + if (serviceId == static_cast(supv::tm::TmtcId::EXEC_ACK)) { + return 1; + } else if (serviceId == static_cast(supv::tm::TmtcId::EXEC_NAK)) { + exeReport.printStatusInformation(); + triggerEvent( + SUPV_EXE_FAILURE_REPORT, + buildApidServiceParam1(exeReport.getRefModuleApid(), exeReport.getRefServiceId()), + exeReport.getStatusCode()); + return -1; + } + // Should never happen + return -1; + } else { + pushIpcData(decodedBuf.data(), packetLen); + decodedRingBuf.deleteData(packetLen); + } + } + return 0; +} + +ReturnValue_t PlocSupvUartManager::checkReceivedTm() { + ReturnValue_t result = tmReader.checkSize(); + if (result != returnvalue::OK) { + triggerEvent(SUPV_REPLY_SIZE_MISSMATCH, rememberApid); + return result; + } + if (not tmReader.verifyCrc()) { + triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); + return result; + } + return result; +} + +ReturnValue_t PlocSupvUartManager::calcImageCrc() { + ReturnValue_t result = returnvalue::OK; + if (update.fullFileSize == 0) { + return returnvalue::FAILED; + } +#ifdef XIPHOS_Q7S + result = FilesystemHelper::checkPath(update.file); + if (result != returnvalue::OK) { + sif::warning << "PlocSupvHelper::calcImageCrc: File " << update.file << " does not exist" + << std::endl; + return result; + } +#endif + + auto crc16Calcer = etl::crc16_ccitt(); + std::ifstream file(update.file, std::ifstream::binary); + std::array crcBuf{}; +#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 + ProgressPrinter progress("Supervisor update crc calculation", update.fullFileSize, + ProgressPrinter::ONE_PERCENT); +#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + uint32_t byteCount = 0; + size_t bytesToRead = 1024; + while (byteCount < update.fullFileSize) { + size_t remLen = update.fullFileSize - byteCount; + if (remLen < 1024) { + bytesToRead = remLen; + } else { + bytesToRead = 1024; + } + file.seekg(byteCount, file.beg); + file.read(reinterpret_cast(crcBuf.data()), bytesToRead); + crc16Calcer.add(crcBuf.begin(), crcBuf.begin() + bytesToRead); + +#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 + progress.print(byteCount); +#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + byteCount += bytesToRead; + } +#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 + progress.print(byteCount); +#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + update.crc = crc16Calcer.value(); + return result; +} + +ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand(uint8_t failStep) { + ReturnValue_t result = returnvalue::OK; + resetSpParams(); + supv::CheckMemory tcPacket(spParams); + result = tcPacket.buildPacket(update.memoryId, update.startAddress, update.fullFileSize); + if (result != returnvalue::OK) { + return result; + } + result = encodeAndSendPacket(tcPacket.getFullPacket(), tcPacket.getFullPacketLen()); + if (result != returnvalue::OK) { + return result; + } + Countdown countdown(timeout::CRC_EXECUTION_TIMEOUT); + bool ackReceived = false; + bool checkReplyReceived = false; + bool packetWasHandled = false; + bool exeReceived = false; + while (true) { + handleUartReception(); + if (not decodedQueue.empty()) { + size_t packetLen = 0; + decodedQueue.retrieve(&packetLen); + decodedRingBuf.readData(decodedBuf.data(), packetLen, true); + tmReader.setData(decodedBuf.data(), packetLen); + result = checkReceivedTm(); + if (result != returnvalue::OK) { + continue; + } + packetWasHandled = false; + if (tmReader.getModuleApid() == Apid::TMTC_MAN) { + int retval = 0; + if (not ackReceived) { + retval = handleAckReception(tcPacket, packetLen); + if (retval == 1) { + packetWasHandled = true; + ackReceived = true; + } else if (retval == -1) { + return returnvalue::FAILED; + } + } else { + retval = handleExeAckReception(tcPacket, packetLen); + if (retval == 1) { + packetWasHandled = true; + exeReceived = true; + } else if (retval == -1) { + return returnvalue::FAILED; + } + } + } else if (tmReader.getModuleApid() == Apid::MEM_MAN) { + if (ackReceived) { + supv::UpdateStatusReport report(tmReader); + result = report.parse(); + if (result != returnvalue::OK) { + return result; + } + packetWasHandled = true; + checkReplyReceived = true; + if (update.crcShouldBeChecked) { + result = report.verifyCrc(update.crc); + if (result == returnvalue::OK) { + triggerEvent(SUPV_MEM_CHECK_OK, result); + } else { + sif::warning + + << "PlocSupvHelper::handleCheckMemoryCommand: CRC failure. Expected CRC 0x" + << std::setfill('0') << std::hex << std::setw(4) + << static_cast(update.crc) << " but received CRC 0x" << std::setw(4) + << report.getCrc() << std::dec << std::endl; + triggerEvent(SUPV_MEM_CHECK_FAIL, result, failStep); + } + } + } + } + if (not packetWasHandled) { + pushIpcData(decodedBuf.data(), packetLen); + decodedRingBuf.deleteData(packetLen); + } + } else { + TaskFactory::delayTask(20); + } + if (ackReceived and exeReceived and checkReplyReceived) { + break; + } + if (countdown.hasTimedOut()) { + return result::NO_REPLY_TIMEOUT; + } + } + return returnvalue::OK; +} + +uint32_t PlocSupvUartManager::getFileSize(std::string filename) { + std::ifstream file(filename, std::ifstream::binary); + file.seekg(0, file.end); + uint32_t size = file.tellg(); + file.close(); + return size; +} + +ReturnValue_t PlocSupvUartManager::handleEventBufferReception(ploc::SpTmReader& reader) { + ReturnValue_t result = returnvalue::OK; + // TODO: Fix + //#ifdef XIPHOS_Q7S + // if (not sdcMan->getActiveSdCard()) { + // return HasFileSystemIF::FILESYSTEM_INACTIVE; + // } + //#endif + // std::string filename = Filenaming::generateAbsoluteFilename( + // eventBufferReq.path, eventBufferReq.filename, timestamping); + // std::ofstream file(filename, std::ios_base::app | std::ios_base::out); + // uint32_t packetsRead = 0; + // size_t requestLen = 0; + // bool firstPacket = true; + // for (packetsRead = 0; packetsRead < NUM_EVENT_BUFFER_PACKETS; packetsRead++) { + // if (terminate) { + // triggerEvent(SUPV_EVENT_BUFFER_REQUEST_TERMINATED, packetsRead - 1); + // file.close(); + // return PROCESS_TERMINATED; + // } + // if (packetsRead == NUM_EVENT_BUFFER_PACKETS - 1) { + // requestLen = SIZE_EVENT_BUFFER_LAST_PACKET; + // } else { + // requestLen = SIZE_EVENT_BUFFER_FULL_PACKET; + // } + // if (firstPacket) { + // firstPacket = false; + // requestLen -= 6; + // } + // result = handleTmReception(requestLen); + // if (result != returnvalue::OK) { + // sif::debug << "PlocSupvHelper::handleEventBufferReception: Failed while trying to read + // packet" + // << " " << packetsRead + 1 << std::endl; + // file.close(); + // return result; + // } + // ReturnValue_t result = reader.checkCrc(); + // if (result != returnvalue::OK) { + // triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); + // return result; + // } + // uint16_t apid = reader.getApid(); + // if (apid != supv::APID_MRAM_DUMP_TM) { + // sif::warning << "PlocSupvHelper::handleEventBufferReception: Did not expect space packet " + // << "with APID 0x" << std::hex << apid << std::endl; + // file.close(); + // return EVENT_BUFFER_REPLY_INVALID_APID; + // } + // // TODO: Fix + // // file.write(reinterpret_cast(reader.getPacketData()), + // // reader.getPayloadDataLength()); + // } + return result; +} + +void PlocSupvUartManager::resetSpParams() { spParams.buf = cmdBuf.data(); } + +ReturnValue_t PlocSupvUartManager::sendMessage(CookieIF* cookie, const uint8_t* sendData, + size_t sendLen) { + if (sendData == nullptr or sendLen == 0) { + return FAILED; + } + { + MutexGuard mg(lock); + if (state == InternalState::SLEEPING or state == InternalState::DEDICATED_REQUEST) { + return FAILED; + } + } + return encodeAndSendPacket(sendData, sendLen); +} + +ReturnValue_t PlocSupvUartManager::getSendSuccess(CookieIF* cookie) { return returnvalue::OK; } + +ReturnValue_t PlocSupvUartManager::requestReceiveMessage(CookieIF* cookie, size_t requestLen) { + return returnvalue::OK; +} + +ReturnValue_t PlocSupvUartManager::handleRunningLongerRequest() { + ReturnValue_t result = OK; + switch (request) { + case Request::UPDATE: { + result = executeUpdate(); + if (result == returnvalue::OK) { + triggerEvent(SUPV_UPDATE_SUCCESSFUL, result); + } else if (result == PROCESS_TERMINATED) { + // Event already triggered + } else { + triggerEvent(SUPV_UPDATE_FAILED, result); + } + break; + } + case Request::CHECK_MEMORY: { + executeFullCheckMemoryCommand(); + break; + } + case Request::CONTINUE_UPDATE: { + result = continueUpdate(); + if (result == returnvalue::OK) { + triggerEvent(SUPV_CONTINUE_UPDATE_SUCCESSFUL, result); + } else if (result == PROCESS_TERMINATED) { + // Event already triggered + } else { + triggerEvent(SUPV_CONTINUE_UPDATE_FAILED, result); + } + break; + } + case Request::REQUEST_EVENT_BUFFER: { + // result = performEventBufferRequest(); + // if (result == returnvalue::OK) { + // triggerEvent(SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL, result); + // } else if (result == PROCESS_TERMINATED) { + // // Event already triggered + // break; + // } else { + // triggerEvent(SUPV_EVENT_BUFFER_REQUEST_FAILED, result); + // } + break; + } + case Request::DEFAULT: { + break; + } + } + return false; +} + +ReturnValue_t PlocSupvUartManager::encodeAndSendPacket(const uint8_t* sendData, size_t sendLen) { + size_t encodedLen = 0; + addHdlcFraming(sendData, sendLen, encodedSendBuf.data(), &encodedLen, encodedSendBuf.size()); + if (printTc) { + sif::debug << "Sending TC" << std::endl; + arrayprinter::print(encodedSendBuf.data(), encodedLen); + } + size_t bytesWritten = write(serialPort, encodedSendBuf.data(), encodedLen); + if (bytesWritten != encodedLen) { + sif::warning + << "PlocSupvUartManager::sendMessage: Sending ping command to solar experiment failed" + << std::endl; + return FAILED; + } + return returnvalue::OK; +} + +ReturnValue_t PlocSupvUartManager::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, + size_t* size) { + MutexGuard mg(ipcLock); + if (ipcQueue.empty()) { + *size = 0; + return OK; + } + ipcQueue.retrieve(size); + *buffer = ipcBuffer.data(); + ReturnValue_t result = ipcRingBuf.readData(ipcBuffer.data(), *size, true); + if (result != OK) { + sif::warning << "PlocSupvHelper::readReceivedMessage: Reading RingBuffer failed" << std::endl; + } + return OK; +} + +ReturnValue_t PlocSupvUartManager::tryHdlcParsing() { + size_t bytesRead = 0; + size_t decodedLen = 0; + ReturnValue_t result = parseRecRingBufForHdlc(bytesRead, decodedLen); + if (result == returnvalue::OK) { + // Packet found, advance read pointer. + if (state == InternalState::DEDICATED_REQUEST) { + decodedRingBuf.writeData(decodedBuf.data(), decodedLen); + decodedQueue.insert(decodedLen); + } else { + MutexGuard mg(ipcLock); + ipcRingBuf.writeData(decodedBuf.data(), decodedLen); + ipcQueue.insert(decodedLen); + } + recRingBuf.deleteData(bytesRead); + } else if (result != NO_PACKET_FOUND) { + sif::warning << "PlocSupvUartMan::performOperation: Possible packet loss" << std::endl; + // Markers found at wrong place + // which might be a hint for a possibly lost packet. + // Maybe trigger event? + recRingBuf.deleteData(bytesRead); + } + return result; +} + +ReturnValue_t PlocSupvUartManager::parseRecRingBufForHdlc(size_t& readSize, size_t& decodedLen) { + size_t availableData = recRingBuf.getAvailableReadData(); + if (availableData == 0) { + return NO_PACKET_FOUND; + } + if (availableData > encodedBuf.size()) { + return DECODE_BUF_TOO_SMALL; + } + ReturnValue_t result = recRingBuf.readData(encodedBuf.data(), availableData); + if (result != returnvalue::OK) { + return result; + } + bool startMarkerFound = false; + size_t startIdx = 0; + for (size_t idx = 0; idx < availableData; idx++) { + // handle start marker + if (encodedBuf[idx] == HDLC_START_MARKER) { + if (not startMarkerFound) { + startMarkerFound = true; + startIdx = idx; + } else { + readSize = idx; + return POSSIBLE_PACKET_LOSS_CONSECUTIVE_START; + } + } + if (encodedBuf[idx] == HDLC_END_MARKER) { + if (startMarkerFound) { + // Probably a packet, so decode it + int retval = removeHdlcFramingWithCrcCheck(encodedBuf.data() + startIdx, idx + 1 - startIdx, + decodedBuf.data(), &decodedLen); + readSize = idx + 1; + if (retval == -1 or retval == -2) { + triggerEvent(HDLC_FRAME_REMOVAL_ERROR, retval); + } else if (retval == 1) { + triggerEvent(HDLC_CRC_ERROR); + } + if (retval != 0) { + return HDLC_ERROR; + } + return returnvalue::OK; + } else { + readSize = ++idx; + return POSSIBLE_PACKET_LOSS_CONSECUTIVE_END; + } + } + } + return NO_PACKET_FOUND; +} + +void PlocSupvUartManager::pushIpcData(const uint8_t* data, size_t len) { + MutexGuard mg(ipcLock); + ipcRingBuf.writeData(data, len); + ipcQueue.insert(len); +} + +uint32_t PlocSupvUartManager::buildApidServiceParam1(uint8_t apid, uint8_t serviceId) { + return (apid << 8) | serviceId; +} + +void PlocSupvUartManager::performUartShutdown() { + tcflush(serialPort, TCIOFLUSH); + // Clear ring buffers + recRingBuf.clear(); + decodedRingBuf.clear(); + while (not decodedQueue.empty()) { + decodedQueue.pop(); + } + MutexGuard mg(ipcLock); + ipcRingBuf.clear(); + while (not ipcQueue.empty()) { + ipcQueue.pop(); + } + state = InternalState::GO_TO_SLEEP; +} + +void PlocSupvUartManager::addHdlcFraming(const uint8_t* src, size_t slen, uint8_t* dst, + size_t* dlen, size_t maxDest) { + size_t tlen = 0; + uint16_t ii; + uint8_t bt; + + // calc crc16 + uint16_t crc16 = calc_crc16_buff_reflected(src, slen); + + dst[tlen++] = 0x7E; + for (ii = 0; ii < slen; ii++) { + bt = *src++; + hdlc_add_byte(bt, dst, &tlen); + } + + size_t dummy = 0; + uint8_t crcRaw[2]; + // hdlc crc16 is in little endian format + SerializeAdapter::serialize(&crc16, crcRaw, &dummy, maxDest, SerializeIF::Endianness::LITTLE); + hdlc_add_byte(crcRaw[0], dst, &tlen); + hdlc_add_byte(crcRaw[1], dst, &tlen); + + dst[tlen++] = 0x7C; + *dlen = tlen; +} + +int PlocSupvUartManager::removeHdlcFramingWithCrcCheck(const uint8_t* src, size_t slen, + uint8_t* dst, size_t* dlen) { + uint16_t tlen = 0; + uint16_t ii; + uint8_t bt; + + *dlen = 0; + if (slen < 4) return -1; + if ((src[tlen] != 0x7E) && (src[slen - 1] != 0x7C)) return -2; + src++; + for (ii = 1; ii < slen - 1; ii++) { + bt = *src++; + + if (bt == 0x7D) { + bt = *src++ ^ 0x20; + ii++; + } + dst[tlen++] = bt; + } + // calc crc16 + uint16_t calcCrc = calc_crc16_buff_reflected(dst, tlen - 2); + uint16_t crc; + size_t dummy; + SerializeAdapter::deSerialize(&crc, dst + tlen - 2, &dummy, SerializeIF::Endianness::LITTLE); + if (calcCrc != crc) { + return 1; + } + // if(calc_crc16_buff_reflected(dst, tlen) != 0) { + // return 1; + // } + *dlen = tlen - 2; + return 0; +} + +bool PlocSupvUartManager::longerRequestActive() const { + MutexGuard mg(lock); + return state == InternalState::DEDICATED_REQUEST; +} + +void PlocSupvUartManager::updateVtime(uint8_t vtime) { + tcgetattr(serialPort, &tty); + tty.c_cc[VTIME] = vtime; + tcsetattr(serialPort, TCSANOW, &tty); +} diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvUartMan.h similarity index 62% rename from linux/devices/ploc/PlocSupvHelper.h rename to linux/devices/ploc/PlocSupvUartMan.h index 43fda22f..e1539c97 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -1,9 +1,13 @@ #ifndef BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_ #define BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_ +#include +#include + #include #include "OBSWConfig.h" +#include "fsfw/container/FIFO.h" #include "fsfw/devicehandlers/CookieIF.h" #include "fsfw/objectmanager/SystemObject.h" #include "fsfw/osal/linux/BinarySemaphore.h" @@ -11,6 +15,7 @@ #include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw_hal/linux/serial/SerialComIF.h" #include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" +#include "tas/crc.h" #ifdef XIPHOS_Q7S #include "bsp_q7s/fs/SdCardManager.h" @@ -21,8 +26,21 @@ * the supervisor and the OBC. * @author J. Meier */ -class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { +class PlocSupvUartManager : public DeviceCommunicationIF, + public SystemObject, + public ExecutableObjectIF { public: + static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_SUPV_HELPER; + + //! [EXPORT] : [COMMENT] File accidentally close + static const ReturnValue_t FILE_CLOSED_ACCIDENTALLY = MAKE_RETURN_CODE(0xA0); + //! [EXPORT] : [COMMENT] Process has been terminated by command + static const ReturnValue_t PROCESS_TERMINATED = MAKE_RETURN_CODE(0xA1); + //! [EXPORT] : [COMMENT] Received command with invalid pathname + static const ReturnValue_t PATH_NOT_EXISTS = MAKE_RETURN_CODE(0xA2); + //! [EXPORT] : [COMMENT] Expected event buffer TM but received space packet with other APID + static const ReturnValue_t EVENT_BUFFER_REPLY_INVALID_APID = MAKE_RETURN_CODE(0xA3); + static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_SUPV_HELPER; //! [EXPORT] : [COMMENT] update failed @@ -97,16 +115,15 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { //! [EXPORT] : [COMMENT] Will be triggered every 5 percent of the update progress. //! P1: First byte percent, third and fourth byte Sequence Count, P2: Bytes written static constexpr Event SUPV_UPDATE_PROGRESS = MAKE_EVENT(30, severity::INFO); + static constexpr Event HDLC_FRAME_REMOVAL_ERROR = MAKE_EVENT(31, severity::INFO); + static constexpr Event HDLC_CRC_ERROR = MAKE_EVENT(32, severity::INFO); - PlocSupvHelper(object_id_t objectId); - virtual ~PlocSupvHelper(); + PlocSupvUartManager(object_id_t objectId); + virtual ~PlocSupvUartManager(); ReturnValue_t initialize() override; ReturnValue_t performOperation(uint8_t operationCode = 0) override; - ReturnValue_t setComIF(SerialComIF* uartComfIF_); - void setComCookie(CookieIF* comCookie_); - /** * @brief Starts update procedure * @@ -119,38 +136,42 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { ReturnValue_t performUpdate(const supv::UpdateParams& params); ReturnValue_t startUpdate(std::string file, uint8_t memoryId, uint32_t startAddress); - ReturnValue_t performMemCheck(uint8_t memoryId, uint32_t startAddress, size_t sizeToCheck, - bool checkCrc); + ReturnValue_t performMemCheck(std::string file, uint8_t memoryId, uint32_t startAddress, + size_t sizeToCheck, bool checkCrc); ReturnValue_t performMemCheck(std::string file, uint8_t memoryId, uint32_t startAddress); /** * @brief This initiate the continuation of a failed update. */ - void initiateUpdateContinuation(); + ReturnValue_t initiateUpdateContinuation(); /** * @brief Calling this function will initiate the procedure to request the event buffer */ - ReturnValue_t startEventbBufferRequest(std::string path); + // ReturnValue_t startEventBufferRequest(std::string path); /** - * @brief Can be used to interrupt a running data transfer. + * @brief Can be used to stop the UART reception and put the task to sleep */ - void stopProcess(); + void stop(); + + /** + * @brief Can be used to start the UART reception + */ + void start(); + bool longerRequestActive() const; static uint32_t buildProgParams1(uint8_t percent, uint16_t seqCount); + static uint32_t buildApidServiceParam1(uint8_t apid, uint8_t serviceId); private: - static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_SUPV_HELPER; - - //! [EXPORT] : [COMMENT] File accidentally close - static const ReturnValue_t FILE_CLOSED_ACCIDENTALLY = MAKE_RETURN_CODE(0xA0); - //! [EXPORT] : [COMMENT] Process has been terminated by command - static const ReturnValue_t PROCESS_TERMINATED = MAKE_RETURN_CODE(0xA1); - //! [EXPORT] : [COMMENT] Received command with invalid pathname - static const ReturnValue_t PATH_NOT_EXISTS = MAKE_RETURN_CODE(0xA2); - //! [EXPORT] : [COMMENT] Expected event buffer TM but received space packet with other APID - static const ReturnValue_t EVENT_BUFFER_REPLY_INVALID_APID = MAKE_RETURN_CODE(0xA3); + static constexpr ReturnValue_t REQUEST_DONE = returnvalue::makeCode(1, 0); + static constexpr ReturnValue_t NO_PACKET_FOUND = returnvalue::makeCode(1, 1); + static constexpr ReturnValue_t DECODE_BUF_TOO_SMALL = returnvalue::makeCode(1, 2); + static constexpr ReturnValue_t POSSIBLE_PACKET_LOSS_CONSECUTIVE_START = + returnvalue::makeCode(1, 3); + static constexpr ReturnValue_t POSSIBLE_PACKET_LOSS_CONSECUTIVE_END = returnvalue::makeCode(1, 4); + static constexpr ReturnValue_t HDLC_ERROR = returnvalue::makeCode(1, 5); static const uint16_t CRC16_INIT = 0xFFFF; // Event buffer reply will carry 24 space packets with 1016 bytes and one space packet with @@ -158,19 +179,22 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { static const uint8_t NUM_EVENT_BUFFER_PACKETS = 25; static const size_t SIZE_EVENT_BUFFER_FULL_PACKET = 1024; static const size_t SIZE_EVENT_BUFFER_LAST_PACKET = 200; - static const uint32_t CRC_EXECUTION_TIMEOUT = 60000; static const uint32_t PREPARE_UPDATE_EXECUTION_REPORT = 2000; + static constexpr uint8_t MAX_STORED_DECODED_PACKETS = 4; + static constexpr uint8_t HDLC_START_MARKER = 0x7E; + static constexpr uint8_t HDLC_END_MARKER = 0x7C; + struct Update { uint8_t memoryId; uint32_t startAddress; // Absolute name of file containing update data std::string file; // Length of full file - size_t fullFileSize; + size_t fullFileSize = 0; // Size of update - uint32_t length; - uint32_t crc; + uint32_t length = 0; + uint32_t crc = 0; bool crcShouldBeChecked = true; size_t bytesWritten; uint32_t packetNum; @@ -181,6 +205,13 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { struct Update update; + SemaphoreIF* semaphore; + MutexIF* lock; + MutexIF* ipcLock; + supv::TmBase tmReader; + int serialPort = 0; + struct termios tty = {}; + struct EventBufferRequest { std::string path = ""; // Default name of file where event buffer data will be written to. Timestamp will be added to @@ -190,54 +221,65 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { EventBufferRequest eventBufferReq; - enum class InternalState { IDLE, UPDATE, CONTINUE_UPDATE, REQUEST_EVENT_BUFFER, CHECK_MEMORY }; + enum class InternalState { SLEEPING, DEFAULT, DEDICATED_REQUEST, GO_TO_SLEEP }; - InternalState internalState = InternalState::IDLE; + enum class Request { + DEFAULT, + UPDATE, + CONTINUE_UPDATE, + REQUEST_EVENT_BUFFER, + CHECK_MEMORY, + }; + InternalState state = InternalState::SLEEPING; + Request request = Request::DEFAULT; - BinarySemaphore semaphore; #ifdef XIPHOS_Q7S SdCardManager* sdcMan = nullptr; #endif - uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]{}; + SimpleRingBuffer recRingBuf; + std::array cmdBuf = {}; + std::array encodedSendBuf = {}; + std::array recBuf = {}; + std::array encodedBuf = {}; + std::array decodedBuf = {}; + std::array ipcBuffer = {}; + SimpleRingBuffer decodedRingBuf; + FIFO decodedQueue; + SimpleRingBuffer ipcRingBuf; + FIFO ipcQueue; + SpacePacketCreator creator; - ploc::SpTcParams spParams = ploc::SpTcParams(creator); + supv::TcParams spParams = supv::TcParams(creator); std::array tmBuf{}; - bool terminate = false; - - /** - * Communication interface responsible for data transactions between OBC and Supervisor. - */ - SerialComIF* uartComIF = nullptr; - // Communication cookie. Must be set by the supervisor Handler - CookieIF* comCookie = nullptr; - + bool printTc = false; + bool debugMode = false; bool timestamping = true; // Remembers APID to know at which command a procedure failed uint16_t rememberApid = 0; + ReturnValue_t handleRunningLongerRequest(); + ReturnValue_t handleUartReception(); + void addHdlcFraming(const uint8_t* src, size_t slen, uint8_t* dst, size_t* dlen, size_t maxDest); + int removeHdlcFramingWithCrcCheck(const uint8_t* src, size_t slen, uint8_t* dst, size_t* dlen); + + ReturnValue_t encodeAndSendPacket(const uint8_t* sendData, size_t sendLen); void executeFullCheckMemoryCommand(); + ReturnValue_t tryHdlcParsing(); + ReturnValue_t parseRecRingBufForHdlc(size_t& readSize, size_t& decodedLen); ReturnValue_t executeUpdate(); ReturnValue_t continueUpdate(); ReturnValue_t updateOperation(); ReturnValue_t writeUpdatePackets(); - ReturnValue_t performEventBufferRequest(); - ReturnValue_t handlePacketTransmission(ploc::SpTcBase& packet, - uint32_t timeoutExecutionReport = 60000); - ReturnValue_t sendCommand(ploc::SpTcBase& packet); - /** - * @brief Function which reads form the communication interface - * - * @param data Pointer to buffer where read data will be written to - * @param raedBytes Actual number of bytes read - * @param requestBytes Number of bytes to read - */ - ReturnValue_t receive(uint8_t* data, size_t* readBytes, size_t requestBytes); - ReturnValue_t handleAck(); - ReturnValue_t handleExe(uint32_t timeout = 1000); + // ReturnValue_t performEventBufferRequest(); + ReturnValue_t handlePacketTransmissionNoReply(supv::TcBase& packet, + uint32_t timeoutExecutionReport); + int handleAckReception(supv::TcBase& tc, size_t packetLen); + int handleExeAckReception(supv::TcBase& tc, size_t packetLen); + /** * @brief Handles reading of TM packets from the communication interface * @@ -250,7 +292,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { */ ReturnValue_t handleTmReception(size_t remainingBytes, uint8_t* readBuf = nullptr, uint32_t timeout = 70000); - ReturnValue_t checkReceivedTm(ploc::SpTmReader& reader); + ReturnValue_t checkReceivedTm(); ReturnValue_t selectMemory(); ReturnValue_t prepareUpdate(); @@ -258,7 +300,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { // Calculates CRC over image. Will be used for verification after update writing has // finished. ReturnValue_t calcImageCrc(); - ReturnValue_t handleCheckMemoryCommand(); + ReturnValue_t handleCheckMemoryCommand(uint8_t failStep); ReturnValue_t exeReportHandling(); /** * @brief Return size of file with name filename @@ -269,9 +311,64 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { */ uint32_t getFileSize(std::string filename); ReturnValue_t handleEventBufferReception(ploc::SpTmReader& reader); - ReturnValue_t handleRemainingExeReport(ploc::SpTmReader& reader); void resetSpParams(); + void pushIpcData(const uint8_t* data, size_t len); + + /** + * @brief Device specific initialization, using the cookie. + * @details + * The cookie is already prepared in the factory. If the communication + * interface needs to be set up in some way and requires cookie information, + * this can be performed in this function, which is called on device handler + * initialization. + * @param cookie + * @return + * - @c returnvalue::OK if initialization was successfull + * - Everything else triggers failure event with returnvalue as parameter 1 + */ + ReturnValue_t initializeInterface(CookieIF* cookie) override; + + /** + * Called by DHB in the SEND_WRITE doSendWrite(). + * This function is used to send data to the physical device + * by implementing and calling related drivers or wrapper functions. + * @param cookie + * @param data + * @param len If this is 0, nothing shall be sent. + * @return + * - @c returnvalue::OK for successfull send + * - Everything else triggers failure event with returnvalue as parameter 1 + */ + ReturnValue_t sendMessage(CookieIF* cookie, const uint8_t* sendData, size_t sendLen) override; + /** + * Called by DHB in the GET_WRITE doGetWrite(). + * Get send confirmation that the data in sendMessage() was sent successfully. + * @param cookie + * @return + * - @c returnvalue::OK if data was sent successfully but a reply is expected + * - NO_REPLY_EXPECTED if data was sent successfully and no reply is expected + * - Everything else to indicate failure + */ + ReturnValue_t getSendSuccess(CookieIF* cookie) override; + /** + * Called by DHB in the SEND_WRITE doSendRead(). + * It is assumed that it is always possible to request a reply + * from a device. If a requestLen of 0 is supplied, no reply was enabled + * and communication specific action should be taken (e.g. read nothing + * or read everything). + * + * @param cookie + * @param requestLen Size of data to read + * @return - @c returnvalue::OK to confirm the request for data has been sent. + * - Everything else triggers failure event with + * returnvalue as parameter 1 + */ + ReturnValue_t requestReceiveMessage(CookieIF* cookie, size_t requestLen) override; + ReturnValue_t readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) override; + + void performUartShutdown(); + void updateVtime(uint8_t vtime); }; #endif /* BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_ */ diff --git a/linux/devices/startracker/ArcsecDatalinkLayer.h b/linux/devices/startracker/ArcsecDatalinkLayer.h index ec8caed9..5681d3ca 100644 --- a/linux/devices/startracker/ArcsecDatalinkLayer.h +++ b/linux/devices/startracker/ArcsecDatalinkLayer.h @@ -1,6 +1,7 @@ #ifndef BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_ #define BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_ +#include "eive/resultClassIds.h" #include "fsfw/returnvalues/returnvalue.h" #include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" diff --git a/linux/devices/startracker/ArcsecJsonParamBase.h b/linux/devices/startracker/ArcsecJsonParamBase.h index 75b160b2..a7a4f421 100644 --- a/linux/devices/startracker/ArcsecJsonParamBase.h +++ b/linux/devices/startracker/ArcsecJsonParamBase.h @@ -5,6 +5,7 @@ #include #include +#include "eive/resultClassIds.h" #include "fsfw/returnvalues/returnvalue.h" #include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" diff --git a/linux/devices/startracker/StarTrackerHandler.cpp b/linux/devices/startracker/StarTrackerHandler.cpp index ff632c99..bede0a45 100644 --- a/linux/devices/startracker/StarTrackerHandler.cpp +++ b/linux/devices/startracker/StarTrackerHandler.cpp @@ -1591,7 +1591,7 @@ void StarTrackerHandler::preparePowerRequest() { void StarTrackerHandler::prepareSwitchToBootloaderCmd() { uint32_t length = 0; - struct RebootActionRequest rebootReq; + struct RebootActionRequest rebootReq {}; arc_pack_reboot_action_req(&rebootReq, commandBuffer, &length); dataLinkLayer.encodeFrame(commandBuffer, length); rawPacket = dataLinkLayer.getEncodedFrame(); diff --git a/linux/fsfwconfig/devices/addresses.cpp b/linux/fsfwconfig/devices/addresses.cpp deleted file mode 100644 index 580818e0..00000000 --- a/linux/fsfwconfig/devices/addresses.cpp +++ /dev/null @@ -1 +0,0 @@ -#include "addresses.h" diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index ee85e05c..fdcc4488 100644 --- a/linux/fsfwconfig/events/translateEvents.cpp +++ b/linux/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 234 translations. + * @brief Auto-generated event translation file. Contains 239 translations. * @details - * Generated on: 2022-11-14 17:10:10 + * Generated on: 2022-11-28 18:24:37 */ #include "translateEvents.h" @@ -129,10 +129,13 @@ const char *RESET_OCCURED_STRING = "RESET_OCCURED"; const char *BOOTING_FIRMWARE_FAILED_STRING = "BOOTING_FIRMWARE_FAILED"; const char *BOOTING_BOOTLOADER_FAILED_STRING = "BOOTING_BOOTLOADER_FAILED"; const char *SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING = "SUPV_MEMORY_READ_RPT_CRC_FAILURE"; +const char *SUPV_UNKNOWN_TM_STRING = "SUPV_UNKNOWN_TM"; +const char *SUPV_UNINIMPLEMENTED_TM_STRING = "SUPV_UNINIMPLEMENTED_TM"; const char *SUPV_ACK_FAILURE_STRING = "SUPV_ACK_FAILURE"; const char *SUPV_EXE_FAILURE_STRING = "SUPV_EXE_FAILURE"; const char *SUPV_CRC_FAILURE_EVENT_STRING = "SUPV_CRC_FAILURE_EVENT"; -const char *SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING = "SUPV_MPSOC_SHUWDOWN_BUILD_FAILED"; +const char *SUPV_HELPER_EXECUTING_STRING = "SUPV_HELPER_EXECUTING"; +const char *SUPV_MPSOC_SHUTDOWN_BUILD_FAILED_STRING = "SUPV_MPSOC_SHUTDOWN_BUILD_FAILED"; const char *SANITIZATION_FAILED_STRING = "SANITIZATION_FAILED"; const char *MOUNTED_SD_CARD_STRING = "MOUNTED_SD_CARD"; const char *SEND_MRAM_DUMP_FAILED_STRING = "SEND_MRAM_DUMP_FAILED"; @@ -222,6 +225,8 @@ const char *WRITE_MEMORY_FAILED_STRING = "WRITE_MEMORY_FAILED"; const char *SUPV_REPLY_SIZE_MISSMATCH_STRING = "SUPV_REPLY_SIZE_MISSMATCH"; const char *SUPV_REPLY_CRC_MISSMATCH_STRING = "SUPV_REPLY_CRC_MISSMATCH"; const char *SUPV_UPDATE_PROGRESS_STRING = "SUPV_UPDATE_PROGRESS"; +const char *HDLC_FRAME_REMOVAL_ERROR_STRING = "HDLC_FRAME_REMOVAL_ERROR"; +const char *HDLC_CRC_ERROR_STRING = "HDLC_CRC_ERROR"; const char *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; const char *REBOOT_SW_STRING = "REBOOT_SW"; const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED"; @@ -487,13 +492,19 @@ const char *translateEvents(Event event) { case (12001): return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING; case (12002): - return SUPV_ACK_FAILURE_STRING; + return SUPV_UNKNOWN_TM_STRING; case (12003): - return SUPV_EXE_FAILURE_STRING; + return SUPV_UNINIMPLEMENTED_TM_STRING; case (12004): - return SUPV_CRC_FAILURE_EVENT_STRING; + return SUPV_ACK_FAILURE_STRING; case (12005): - return SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING; + return SUPV_EXE_FAILURE_STRING; + case (12006): + return SUPV_CRC_FAILURE_EVENT_STRING; + case (12007): + return SUPV_HELPER_EXECUTING_STRING; + case (12008): + return SUPV_MPSOC_SHUTDOWN_BUILD_FAILED_STRING; case (12100): return SANITIZATION_FAILED_STRING; case (12101): @@ -672,6 +683,10 @@ const char *translateEvents(Event event) { return SUPV_REPLY_CRC_MISSMATCH_STRING; case (13630): return SUPV_UPDATE_PROGRESS_STRING; + case (13631): + return HDLC_FRAME_REMOVAL_ERROR_STRING; + case (13632): + return HDLC_CRC_ERROR_STRING; case (13700): return ALLOC_FAILURE_STRING; case (13701): diff --git a/linux/fsfwconfig/objects/systemObjectList.h b/linux/fsfwconfig/objects/systemObjectList.h index dba8c630..8f36b013 100644 --- a/linux/fsfwconfig/objects/systemObjectList.h +++ b/linux/fsfwconfig/objects/systemObjectList.h @@ -45,10 +45,8 @@ enum sourceObjects : uint32_t { ARDUINO_COM_IF = 0x49000000, CSP_COM_IF = 0x49050001, I2C_COM_IF = 0x49040002, - UART_COM_IF = 0x49030003, SPI_MAIN_COM_IF = 0x49020004, GPIO_IF = 0x49010005, - SCEX_UART_READER = 0x49010006, /* Custom device handler */ SPI_RW_COM_IF = 0x49020005, diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index 96a2d656..f6e58aab 100644 --- a/linux/fsfwconfig/objects/translateObjects.cpp +++ b/linux/fsfwconfig/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 148 translations. - * Generated on: 2022-11-14 17:10:10 + * Generated on: 2022-11-28 18:24:37 */ #include "translateObjects.h" diff --git a/linux/InitMission.cpp b/linux/scheduling.cpp similarity index 77% rename from linux/InitMission.cpp rename to linux/scheduling.cpp index 4b7dc1f1..f2e6ddec 100644 --- a/linux/InitMission.cpp +++ b/linux/scheduling.cpp @@ -1,4 +1,4 @@ -#include "InitMission.h" +#include "scheduling.h" #include #include @@ -10,7 +10,7 @@ void scheduling::schedulingScex(TaskFactory& factory, PeriodicTaskIF*& scexDevHandler, PeriodicTaskIF*& scexReaderTask) { - using namespace initmission; + using namespace scheduling; ReturnValue_t result = returnvalue::OK; #if OBSW_PRINT_MISSED_DEADLINES == 1 void (*missedDeadlineFunc)(void) = TaskFactory::printMissedDeadline; @@ -37,6 +37,17 @@ void scheduling::schedulingScex(TaskFactory& factory, PeriodicTaskIF*& scexDevHa printAddObjectError("SCEX_DEV", objects::SCEX); } result = scexDevHandler->addComponent(objects::SCEX, DeviceHandlerIF::GET_READ); + if (result != returnvalue::OK) { + printAddObjectError("SCEX_DEV", objects::SCEX); + } + result = scexDevHandler->addComponent(objects::SCEX, DeviceHandlerIF::SEND_READ); + if (result != returnvalue::OK) { + printAddObjectError("SCEX_DEV", objects::SCEX); + } + result = scexDevHandler->addComponent(objects::SCEX, DeviceHandlerIF::GET_READ); + if (result != returnvalue::OK) { + printAddObjectError("SCEX_DEV", objects::SCEX); + } result = returnvalue::OK; scexReaderTask = factory.createPeriodicTask( @@ -50,17 +61,21 @@ void scheduling::schedulingScex(TaskFactory& factory, PeriodicTaskIF*& scexDevHa void scheduling::addMpsocSupvHandlers(PeriodicTaskIF* plTask) { #if OBSW_ADD_PLOC_SUPERVISOR == 1 plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::PERFORM_OPERATION); - plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::SEND_READ); - plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::GET_READ); plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::SEND_WRITE); plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::GET_WRITE); + plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::SEND_READ); + plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::GET_READ); + plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::SEND_READ); + plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::GET_READ); #endif #if OBSW_ADD_PLOC_MPSOC == 1 plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::PERFORM_OPERATION); - plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::SEND_READ); - plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::GET_READ); plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::SEND_WRITE); plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::GET_WRITE); + plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::SEND_READ); + plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::GET_READ); + plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::SEND_READ); + plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::GET_READ); #endif } diff --git a/linux/InitMission.h b/linux/scheduling.h similarity index 100% rename from linux/InitMission.h rename to linux/scheduling.h index dd809ff7..d33e9d1f 100644 --- a/linux/InitMission.h +++ b/linux/scheduling.h @@ -1,9 +1,9 @@ #pragma once + #include namespace scheduling { void schedulingScex(TaskFactory& factory, PeriodicTaskIF*& scexDevHandler, PeriodicTaskIF*& scexReaderTask); void addMpsocSupvHandlers(PeriodicTaskIF* task); - } // namespace scheduling diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index 0e1926f4..114451b2 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -99,12 +99,12 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun #if OBSW_ADD_TCPIP_BRIDGE == 1 #if OBSW_USE_TMTC_TCP_BRIDGE == 0 - auto tcpIpTmtcBridge = new UdpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR); + auto tmtcBridge = new UdpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR); new UdpTcPollingTask(objects::TMTC_POLLING_TASK, objects::TMTC_BRIDGE); sif::info << "Created UDP server for TMTC commanding with listener port " - << udpBridge->getUdpPort() << std::endl; + << tmtcBridge->getUdpPort() << std::endl; #else - auto tcpIpTmtcBridge = new TcpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR); + auto tmtcBridge = new TcpTmTcBridge(objects::TMTC_BRIDGE, objects::CCSDS_PACKET_DISTRIBUTOR); auto tcpServer = new TcpTmTcServer(objects::TMTC_POLLING_TASK, objects::TMTC_BRIDGE); // TCP is stream based. Use packet ID as start marker when parsing for space packets tcpServer->setSpacePacketParsingOptions({common::PUS_PACKET_ID, common::CFDP_PACKET_ID}); @@ -114,7 +114,7 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun tcpServer->enableWiretapping(true); #endif /* OBSW_TCP_SERVER_WIRETAPPING == 1 */ #endif /* OBSW_USE_TMTC_TCP_BRIDGE == 0 */ - tcpIpTmtcBridge->setMaxNumberOfPacketsStored(150); + tmtcBridge->setMaxNumberOfPacketsStored(150); #endif /* OBSW_ADD_TCPIP_BRIDGE == 1 */ auto* ccsdsDistrib = @@ -124,8 +124,8 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_, PusTmFun *cfdpFunnel = new CfdpTmFunnel(objects::CFDP_TM_FUNNEL, config::EIVE_CFDP_APID, *tmStore, 50); *pusFunnel = new PusTmFunnel(objects::PUS_TM_FUNNEL, *timeStamper, *tmStore, 80); #if OBSW_ADD_TCPIP_BRIDGE == 1 - (*cfdpFunnel)->addDestination(*tcpIpTmtcBridge, 0); - (*pusFunnel)->addDestination(*tcpIpTmtcBridge, 0); + (*cfdpFunnel)->addDestination(*tmtcBridge, 0); + (*pusFunnel)->addDestination(*tmtcBridge, 0); #endif // Every TM packet goes through this funnel new TmFunnelHandler(objects::TM_FUNNEL, **pusFunnel, **cfdpFunnel); diff --git a/mission/devices/devicedefinitions/SpBase.h b/mission/devices/devicedefinitions/SpBase.h index caa14d5f..11d67a59 100644 --- a/mission/devices/devicedefinitions/SpBase.h +++ b/mission/devices/devicedefinitions/SpBase.h @@ -14,43 +14,48 @@ struct SpTcParams { SpTcParams(SpacePacketCreator& creator, uint8_t* buf, size_t maxSize) : creator(creator), buf(buf), maxSize(maxSize) {} - void setPayloadLen(size_t payloadLen_) { dataFieldLen = payloadLen_ + 2; } - - void setDataFieldLen(size_t dataFieldLen_) { dataFieldLen = dataFieldLen_; } + void setFullPayloadLen(size_t fullPayloadLen_) { fullPayloadLen = fullPayloadLen_; } SpacePacketCreator& creator; uint8_t* buf = nullptr; size_t maxSize = 0; - size_t dataFieldLen = 0; + size_t fullPayloadLen = 0; }; class SpTcBase { public: - SpTcBase(SpTcParams params) : spParams(params) { - payloadStart = spParams.buf + ccsds::HEADER_LEN; - updateSpFields(); - } + SpTcBase(SpTcParams params) : SpTcBase(params, 0x00, 1, 0) {} - SpTcBase(SpTcParams params, uint16_t apid, uint16_t seqCount) : spParams(params) { + SpTcBase(SpTcParams params, uint16_t apid, size_t payloadLen) + : SpTcBase(params, apid, payloadLen, 0) {} + + SpTcBase(SpTcParams params, uint16_t apid, size_t payloadLen, uint16_t seqCount) + : spParams(params) { spParams.creator.setApid(apid); spParams.creator.setSeqCount(seqCount); payloadStart = spParams.buf + ccsds::HEADER_LEN; + spParams.fullPayloadLen = payloadLen; updateSpFields(); } void updateSpFields() { - spParams.creator.setDataLenField(spParams.dataFieldLen - 1); + updateLenFromParams(); spParams.creator.setPacketType(ccsds::PacketType::TC); } + void updateLenFromParams() { spParams.creator.setDataLenField(spParams.fullPayloadLen - 1); } const uint8_t* getFullPacket() const { return spParams.buf; } + const uint8_t* getPacketData() const { return spParams.buf + ccsds::HEADER_LEN; } + size_t getFullPacketLen() const { return spParams.creator.getFullPacketLen(); } uint16_t getApid() const { return spParams.creator.getApid(); } + uint16_t getSeqCount() const { return spParams.creator.getSequenceCount(); } + ReturnValue_t checkPayloadLen() { - if (ccsds::HEADER_LEN + spParams.dataFieldLen > spParams.maxSize) { + if (ccsds::HEADER_LEN + spParams.fullPayloadLen > spParams.maxSize) { return SerializeIF::BUFFER_TOO_SHORT; } @@ -71,7 +76,7 @@ class SpTcBase { return serializeHeader(); } - ReturnValue_t calcCrc() { + ReturnValue_t calcAndSetCrc() { /* Calculate crc */ uint16_t crc = CRC::crc16ccitt(spParams.buf, getFullPacketLen() - 2); @@ -101,12 +106,7 @@ class SpTmReader : public SpacePacketReader { return setReadOnlyData(buf, maxSize); } - /** - * @brief Returns the payload data length (data field length without CRC) - */ - uint16_t getPayloadDataLength() { return getPacketDataLen() - 2; } - - ReturnValue_t checkCrc() { + ReturnValue_t checkCrc() const { if (CRC::crc16ccitt(getFullData(), getFullPacketLen()) != 0) { return returnvalue::FAILED; } diff --git a/mission/utility/InitMission.h b/mission/utility/InitMission.h index 5529f749..85d8ae21 100644 --- a/mission/utility/InitMission.h +++ b/mission/utility/InitMission.h @@ -3,7 +3,7 @@ #include #include -namespace initmission { +namespace scheduling { static void printAddObjectError(const char* name, object_id_t objectId) { #if FSFW_CPP_OSTREAM_ENABLED == 1 @@ -16,4 +16,4 @@ static void printAddObjectError(const char* name, object_id_t objectId) { #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ } -} // namespace initmission +} // namespace scheduling diff --git a/scripts/q7s-cp.py b/scripts/q7s-cp.py index 2890a46d..7a4f7405 100755 --- a/scripts/q7s-cp.py +++ b/scripts/q7s-cp.py @@ -17,7 +17,9 @@ def main(): def prompt_ssh_key_removal(): - do_remove_key = input("Do you want to remove problematic keys on localhost ([Y]/n)?: ") + do_remove_key = input( + "Do you want to remove problematic keys on localhost ([Y]/n)?: " + ) if not do_remove_key.lower() in ["y", "yes", "1", ""]: sys.exit(1) port = 0 @@ -65,7 +67,7 @@ def handle_args(): "--flatsat", default=False, action="store_true", - help="Copy to flatsat instead" + help="Copy to flatsat instead", ) # Positional argument(s) parser.add_argument( @@ -86,7 +88,7 @@ def build_cmd(args): address = "eive@flatsat.eive.absatvirt.lw" else: address = "root@localhost" - port_args=f"-P {args.port}" + port_args = f"-P {args.port}" if args.invert: if target == "": target = "." diff --git a/thirdparty/CMakeLists.txt b/thirdparty/CMakeLists.txt index 68ea851d..7455bdae 100644 --- a/thirdparty/CMakeLists.txt +++ b/thirdparty/CMakeLists.txt @@ -1 +1,5 @@ +if(EIVE_ADD_LINUX_FILES) + add_subdirectory(tas) +endif() + add_subdirectory(rapidcsv) diff --git a/thirdparty/tas/CMakeLists.txt b/thirdparty/tas/CMakeLists.txt new file mode 100644 index 00000000..ab4e75e7 --- /dev/null +++ b/thirdparty/tas/CMakeLists.txt @@ -0,0 +1,9 @@ +target_sources(${OBSW_NAME} PRIVATE + hdlc.c + uart.c + crc.c +) + +target_include_directories(${OBSW_NAME} PRIVATE + ${CMAKE_CURRENT_SOURCE_DIR} +) diff --git a/thirdparty/tas/crc.c b/thirdparty/tas/crc.c new file mode 100644 index 00000000..5a50a3a8 --- /dev/null +++ b/thirdparty/tas/crc.c @@ -0,0 +1,195 @@ +/*************************************************************************************** +* \copyright: 2020-2022 Thales Alenia Space Deutschland GmbH +* \project: multiMIND +* \file: crc.c +* \date: 22.02.2022 +* \author: David Woodward +* \brief: CRC algorithms +***************************************************************************************/ + +#include +#include "tas/crc.h" + + +const uint16_t crc16_0x1021_table[256] = { + 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7, + 0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF, + 0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6, + 0x9339, 0x8318, 0xB37B, 0xA35A, 0xD3BD, 0xC39C, 0xF3FF, 0xE3DE, + 0x2462, 0x3443, 0x0420, 0x1401, 0x64E6, 0x74C7, 0x44A4, 0x5485, + 0xA56A, 0xB54B, 0x8528, 0x9509, 0xE5EE, 0xF5CF, 0xC5AC, 0xD58D, + 0x3653, 0x2672, 0x1611, 0x0630, 0x76D7, 0x66F6, 0x5695, 0x46B4, + 0xB75B, 0xA77A, 0x9719, 0x8738, 0xF7DF, 0xE7FE, 0xD79D, 0xC7BC, + 0x48C4, 0x58E5, 0x6886, 0x78A7, 0x0840, 0x1861, 0x2802, 0x3823, + 0xC9CC, 0xD9ED, 0xE98E, 0xF9AF, 0x8948, 0x9969, 0xA90A, 0xB92B, + 0x5AF5, 0x4AD4, 0x7AB7, 0x6A96, 0x1A71, 0x0A50, 0x3A33, 0x2A12, + 0xDBFD, 0xCBDC, 0xFBBF, 0xEB9E, 0x9B79, 0x8B58, 0xBB3B, 0xAB1A, + 0x6CA6, 0x7C87, 0x4CE4, 0x5CC5, 0x2C22, 0x3C03, 0x0C60, 0x1C41, + 0xEDAE, 0xFD8F, 0xCDEC, 0xDDCD, 0xAD2A, 0xBD0B, 0x8D68, 0x9D49, + 0x7E97, 0x6EB6, 0x5ED5, 0x4EF4, 0x3E13, 0x2E32, 0x1E51, 0x0E70, + 0xFF9F, 0xEFBE, 0xDFDD, 0xCFFC, 0xBF1B, 0xAF3A, 0x9F59, 0x8F78, + 0x9188, 0x81A9, 0xB1CA, 0xA1EB, 0xD10C, 0xC12D, 0xF14E, 0xE16F, + 0x1080, 0x00A1, 0x30C2, 0x20E3, 0x5004, 0x4025, 0x7046, 0x6067, + 0x83B9, 0x9398, 0xA3FB, 0xB3DA, 0xC33D, 0xD31C, 0xE37F, 0xF35E, + 0x02B1, 0x1290, 0x22F3, 0x32D2, 0x4235, 0x5214, 0x6277, 0x7256, + 0xB5EA, 0xA5CB, 0x95A8, 0x8589, 0xF56E, 0xE54F, 0xD52C, 0xC50D, + 0x34E2, 0x24C3, 0x14A0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405, + 0xA7DB, 0xB7FA, 0x8799, 0x97B8, 0xE75F, 0xF77E, 0xC71D, 0xD73C, + 0x26D3, 0x36F2, 0x0691, 0x16B0, 0x6657, 0x7676, 0x4615, 0x5634, + 0xD94C, 0xC96D, 0xF90E, 0xE92F, 0x99C8, 0x89E9, 0xB98A, 0xA9AB, + 0x5844, 0x4865, 0x7806, 0x6827, 0x18C0, 0x08E1, 0x3882, 0x28A3, + 0xCB7D, 0xDB5C, 0xEB3F, 0xFB1E, 0x8BF9, 0x9BD8, 0xABBB, 0xBB9A, + 0x4A75, 0x5A54, 0x6A37, 0x7A16, 0x0AF1, 0x1AD0, 0x2AB3, 0x3A92, + 0xFD2E, 0xED0F, 0xDD6C, 0xCD4D, 0xBDAA, 0xAD8B, 0x9DE8, 0x8DC9, + 0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1, + 0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8, + 0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0 +}; + +const uint16_t crc16_0x1021_table_reverse[256] = +{ + 0x0000, 0x1189, 0x2312, 0x329B, 0x4624, 0x57AD, 0x6536, 0x74BF, + 0x8C48, 0x9DC1, 0xAF5A, 0xBED3, 0xCA6C, 0xDBE5, 0xE97E, 0xF8F7, + 0x1081, 0x0108, 0x3393, 0x221A, 0x56A5, 0x472C, 0x75B7, 0x643E, + 0x9CC9, 0x8D40, 0xBFDB, 0xAE52, 0xDAED, 0xCB64, 0xF9FF, 0xE876, + 0x2102, 0x308B, 0x0210, 0x1399, 0x6726, 0x76AF, 0x4434, 0x55BD, + 0xAD4A, 0xBCC3, 0x8E58, 0x9FD1, 0xEB6E, 0xFAE7, 0xC87C, 0xD9F5, + 0x3183, 0x200A, 0x1291, 0x0318, 0x77A7, 0x662E, 0x54B5, 0x453C, + 0xBDCB, 0xAC42, 0x9ED9, 0x8F50, 0xFBEF, 0xEA66, 0xD8FD, 0xC974, + 0x4204, 0x538D, 0x6116, 0x709F, 0x0420, 0x15A9, 0x2732, 0x36BB, + 0xCE4C, 0xDFC5, 0xED5E, 0xFCD7, 0x8868, 0x99E1, 0xAB7A, 0xBAF3, + 0x5285, 0x430C, 0x7197, 0x601E, 0x14A1, 0x0528, 0x37B3, 0x263A, + 0xDECD, 0xCF44, 0xFDDF, 0xEC56, 0x98E9, 0x8960, 0xBBFB, 0xAA72, + 0x6306, 0x728F, 0x4014, 0x519D, 0x2522, 0x34AB, 0x0630, 0x17B9, + 0xEF4E, 0xFEC7, 0xCC5C, 0xDDD5, 0xA96A, 0xB8E3, 0x8A78, 0x9BF1, + 0x7387, 0x620E, 0x5095, 0x411C, 0x35A3, 0x242A, 0x16B1, 0x0738, + 0xFFCF, 0xEE46, 0xDCDD, 0xCD54, 0xB9EB, 0xA862, 0x9AF9, 0x8B70, + 0x8408, 0x9581, 0xA71A, 0xB693, 0xC22C, 0xD3A5, 0xE13E, 0xF0B7, + 0x0840, 0x19C9, 0x2B52, 0x3ADB, 0x4E64, 0x5FED, 0x6D76, 0x7CFF, + 0x9489, 0x8500, 0xB79B, 0xA612, 0xD2AD, 0xC324, 0xF1BF, 0xE036, + 0x18C1, 0x0948, 0x3BD3, 0x2A5A, 0x5EE5, 0x4F6C, 0x7DF7, 0x6C7E, + 0xA50A, 0xB483, 0x8618, 0x9791, 0xE32E, 0xF2A7, 0xC03C, 0xD1B5, + 0x2942, 0x38CB, 0x0A50, 0x1BD9, 0x6F66, 0x7EEF, 0x4C74, 0x5DFD, + 0xB58B, 0xA402, 0x9699, 0x8710, 0xF3AF, 0xE226, 0xD0BD, 0xC134, + 0x39C3, 0x284A, 0x1AD1, 0x0B58, 0x7FE7, 0x6E6E, 0x5CF5, 0x4D7C, + 0xC60C, 0xD785, 0xE51E, 0xF497, 0x8028, 0x91A1, 0xA33A, 0xB2B3, + 0x4A44, 0x5BCD, 0x6956, 0x78DF, 0x0C60, 0x1DE9, 0x2F72, 0x3EFB, + 0xD68D, 0xC704, 0xF59F, 0xE416, 0x90A9, 0x8120, 0xB3BB, 0xA232, + 0x5AC5, 0x4B4C, 0x79D7, 0x685E, 0x1CE1, 0x0D68, 0x3FF3, 0x2E7A, + 0xE70E, 0xF687, 0xC41C, 0xD595, 0xA12A, 0xB0A3, 0x8238, 0x93B1, + 0x6B46, 0x7ACF, 0x4854, 0x59DD, 0x2D62, 0x3CEB, 0x0E70, 0x1FF9, + 0xF78F, 0xE606, 0xD49D, 0xC514, 0xB1AB, 0xA022, 0x92B9, 0x8330, + 0x7BC7, 0x6A4E, 0x58D5, 0x495C, 0x3DE3, 0x2C6A, 0x1EF1, 0x0F78 +}; + +// CRC-32 calculation from original implementation (Sarthak) +// The used algorithm is (most likely) CRC32/BZIP2, as found here: +// https://www.cl.cam.ac.uk/research/srg/projects/fairisle/bluebook/21/crc/node6.html +uint32_t Crc32(const uint8_t *msg, int numBytes, uint32_t remainder) { + + int byte; + unsigned char bit; + + // Perform modulo-2 division, a byte at a time. + for (byte = 0; byte < numBytes; ++byte) + { + // Bring the next byte into the remainder. + remainder ^= (*(msg + byte) << 16); + + // Perform modulo-2 division, a bit at a time. + for (bit = 8; bit > 0; --bit) { + + // Try to divide the current data bit. + if (remainder & CRC32_TOPBIT) { + remainder = (remainder << 1) ^ CRC32_POLYNOMIAL; + } + else { + remainder = (remainder << 1); + } + } + } + + // The final remainder is the CRC result. + return remainder; +} + +// ref.: CRC-16/CCITT-FALSE, alias: CRC-16/AUTOSAR +// https://reveng.sourceforge.io/crc-catalogue/16.htm#crc.cat.crc-16-xmodem +// initial: 0xFFFF, xorOut: 0x0000, RefIn: false, RefOut: false, polynomial: 0x1021 +uint16_t calc_crc16_unreflected(const uint8_t *data, uint32_t len, uint16_t remainder, uint16_t final_xor) +{ + uint16_t crc = remainder; + uint16_t temp; + + // unreflected + while (len-- != 0) + { + temp = (*data++ ^ (crc >> 8)) & 0xff; + crc = crc16_0x1021_table[temp] ^ (crc << 8); + } + + crc ^= final_xor; + + return crc; +} + +void calc_crc16_byte_unreflected(uint16_t *crc16, uint8_t bt) +{ + uint16_t temp; + temp = *crc16; + + // unreflected + *crc16 = crc16_0x1021_table[((temp >> 8) ^ bt) & 0xff] ^ (temp << 8); +} + +// initial: 0xFFFF, xorOut: 0x0000, RefIn: false, RefOut: false, polynomial: 0x1021 +uint16_t calc_crc16_buff_unreflected(uint8_t *data, uint16_t len) +{ + uint16_t crc16 = 0xFFFF; + + // unreflected + while (len-- != 0) + { + crc16 = crc16_0x1021_table[((crc16 >> 8) ^ *data++) & 0xff] ^ (crc16 << 8); + } + + return crc16; +} + +// ref.: CRC-16/X25 +// initial: 0xFFFF, xorOut: 0xFFFF, RefIn: true, RefOut: true, polynomial: 0x1021 +uint16_t calc_crc16_reflected(const uint8_t *data, uint32_t len, uint16_t remainder, uint16_t final_xor) +{ + uint16_t crc16 = remainder; + + // reflected + while (len-- != 0) + { + crc16 = crc16_0x1021_table_reverse[(crc16 ^ *data++) & 0xff] ^ (crc16 >> 8); + } + + return (crc16 ^ final_xor); +} + +void calc_crc16_byte_reflected(uint16_t *crc16, uint8_t bt) +{ + uint16_t temp; + temp = *crc16; + + // reflected + *crc16 = crc16_0x1021_table_reverse[(temp ^ bt) & 0xff] ^ (temp >> 8); +} + +// initial: 0xFFFF, xorOut: 0xFFFF, RefIn: true, RefOut: true, polynomial: 0x1021 +uint16_t calc_crc16_buff_reflected(const uint8_t *data, uint16_t len) +{ + uint16_t crc16 = 0xFFFF; + + // reflected + while (len-- != 0) + { + crc16 = crc16_0x1021_table_reverse[(crc16 ^ *data++) & 0xff] ^ (crc16 >> 8); + } + + return (crc16 ^ 0xFFFF); +} diff --git a/thirdparty/tas/hdlc.c b/thirdparty/tas/hdlc.c new file mode 100644 index 00000000..92f9817f --- /dev/null +++ b/thirdparty/tas/hdlc.c @@ -0,0 +1,90 @@ +//************************************************************************************** +/*! \copyright: 2020-2021 Thales Alenia Space Deutschland GmbH +* \project: multiMIND +* \file: (name of source file: hdlc.c) +* \date: (09.02.2022) +* \author: (Stelios Filippopoulos) +* \brief: (hdlc functions) +* \language: (C) +************************************************************************************** +*/ + +#include "tas/hdlc.h" +#include "tas/crc.h" + +#include + +void hdlc_add_byte(uint8_t ch, uint8_t *buff, size_t *pos) +{ + size_t templen = *pos; + + if ((ch == 0x7E) || + (ch == 0x7D) || + (ch == 0x7C)) + { + buff[templen++] = 0x7D; + ch ^= 0x20; + } + buff[templen++] = ch; + + *pos = templen; +} + +void hdlc_add_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen) +{ + size_t tlen = 0; + uint16_t ii; + uint16_t crc16; + uint8_t bt; + + // calc crc16 + crc16 = calc_crc16_buff_reflected( src, slen ); + + dst[tlen++] = 0x7E; + for (ii = 0; ii < slen; ii++) + { + bt = *src++; + hdlc_add_byte(bt, dst, &tlen); + } + + // hdlc crc16 is in little endian format + // WARNING: This is not portable code! Bytes need to be swapped on a big + // endian system + // TODO: Fix + hdlc_add_byte((uint8_t) (crc16 & 0xFF), dst, &tlen); + hdlc_add_byte((uint8_t) ((crc16 >> 8) & 0xFF), dst, &tlen); + + dst[tlen++] = 0x7C; + *dlen = tlen; +} + +int hdlc_remove_framing_with_crc_check(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen) +{ + uint16_t tlen = 0; + uint16_t ii; + uint8_t bt; + + *dlen = 0; + if (slen < 4) return -1; + if ((src[tlen] != 0x7E) && (src[slen-1] != 0x7C)) return -2; + src++; + for (ii = 1; ii < slen-1; ii++) + { + bt = *src++; + + if (bt == 0x7D) + { + bt = *src++ ^ 0x20; + ii++; + } + dst[tlen++] = bt; + } + // calc crc16 + if(calc_crc16_buff_reflected( dst, tlen ) != 0x0f47) { + return 1; + } + *dlen = tlen - 2; + return 0; +} + + diff --git a/thirdparty/tas/tas/crc.h b/thirdparty/tas/tas/crc.h new file mode 100644 index 00000000..0a45653c --- /dev/null +++ b/thirdparty/tas/tas/crc.h @@ -0,0 +1,116 @@ +/*************************************************************************************** +* \copyright: 2020-2022 Thales Alenia Space Deutschland GmbH +* \project: multiMIND +* \file: crc.c +* \date: 22.02.2022 +* \author: David Woodward +* \brief: CRC algorithms +***************************************************************************************/ + +#ifndef TAS_D_C_CRC_H +#define TAS_D_C_CRC_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include + +// NOTE: These defines are in the header as some are needed for (initial) crc function calls +//CRC-32/BZIP2 +#define CRC32_TOPBIT (1UL<<31) +#define CRC32_POLYNOMIAL 0x04C11DB7 +#define CRC32_INITIAL_REMAINDER 0xFFFFFFFF +#define CRC32_FINAL_XOR_VALUE 0xFFFFFFFF + +// CRC-16/CCITT-FALSE +#define CRC16_INITIAL_REMAINDER 0xFFFF +#define CRC16_FINAL_XOR_VALUE 0x0 + +extern const uint16_t crc16_0x1021_table[256]; + +extern const uint16_t crc16_0x1021_table_reverse[256]; + +/** + * \brief CRC-32/BZIP2 algorithm + */ +uint32_t Crc32(const uint8_t *msg, int numBytes, uint32_t remainder); + + +/** + * \brief CRC-16/CCITT-FALSE (alias CRC-16/AUTOSAR) algorithm, +// initial: 0xFFFF, xorOut: 0x0000, RefIn: false, RefOut: false, polynomial: 0x1021 + * using a lookup table + * \param data Data + * \param len Data length + * \param remainder Remainder to be used, + * use initial remainder for non coherent/standalone calculations + * \param final_xor The value that the final result will be xored + * \return CRC result + */ +uint16_t calc_crc16_unreflected(const uint8_t *data, uint32_t len, uint16_t remainder, uint16_t final_xor); + +/** + * generates a 16-bit CRC for the said data + * + * @param data input data for CRC + * @param len length of the data + * @return crc Generated 16-bit CRC + */ +void calc_crc16_byte_unreflected(uint16_t *crc16, uint8_t bt); + +/** + * \brief CRC-16/CCITT-FALSE (alias CRC-16/AUTOSAR) algorithm, + * polynomial: 0x1021, initial: 0xFFFF, final xor: 0x0, + * using a lookup table + * \param data Data + * \param len Data length + * \param remainder Remainder to be used, + * use initial remainder for non coherent/standalone calculations + * \param final_xor The value that the final result will be xored + * \return CRC result + */ +uint16_t calc_crc16_buff_unreflected(uint8_t *data, uint16_t len); + +/** + * \brief CRC-16/X25 algorithm, + * initial: 0xFFFF, xorOut: 0xFFFF, RefIn: true, RefOut: true, polynomial: 0x1021 + * using a lookup table + * \param data Data + * \param len Data length + * \param remainder Remainder to be used, + * use initial remainder for non coherent/standalone calculations + * \param final_xor The value that the final result will be xored + * \return CRC result + */ +uint16_t calc_crc16_reflected(const uint8_t *data, uint32_t len, uint16_t remainder, uint16_t final_xor); + +/** + * \brief CRC-16/X25 algorithm, + * calculates the crc16 for the next byte, given an already calculated crc16 + * + * @param *crc16 : calculated crc16 - the value will be updated + * @param bt : next byte for crc16 calculation + * @return none + */ +void calc_crc16_byte_reflected(uint16_t *crc16, uint8_t bt); + +/** + * \brief CRC-16/X25 algorithm, + * initial: 0xFFFF, xorOut: 0xFFFF, RefIn: true, RefOut: true, polynomial: 0x1021 + * using a lookup table + * \param data Data + * \param len Data length + * \param remainder Remainder to be used, + * use initial remainder for non coherent/standalone calculations + * \param final_xor The value that the final result will be xored + * \return CRC result + */ +uint16_t calc_crc16_buff_reflected(const uint8_t *data, uint16_t len); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/thirdparty/tas/tas/hdlc.h b/thirdparty/tas/tas/hdlc.h new file mode 100644 index 00000000..b137fc4c --- /dev/null +++ b/thirdparty/tas/tas/hdlc.h @@ -0,0 +1,52 @@ +//************************************************************************************** +/*! \copyright: 2020-2021 Thales Alenia Space Deutschland GmbH +* \project: multiMIND +* \file: (name of source file: hdlc.h) +* \date: (09.02.2022) +* \author: (Stelios Filippopoulos) +* \brief: (hdlc header file) +* \language: (C) +************************************************************************************** +*/ + +#ifndef LIB_HDLC_H_ +#define LIB_HDLC_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include + +#define HDLC_ENABLE + +#define HDLC_START_BYTE (0x7Eu) +#define HDLC_ESC_BYTE (0x7Du) +#define HDLC_END_BYTE (0x7Cu) +#define HDLC_ESCAPE_CHAR (0x20u) + +void hdlc_add_byte(uint8_t ch, uint8_t *buff, size_t *pos); + +void hdlc_add_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen); + +/** + * Decode a HDLC frame, including CRC check and CRC removal in addition + * to the removal of the frame markers. + * @param src + * @param slen + * @param dst + * @param dlen + * @return + * -1 Invalid source length + * -2 No start marker at first byte or end marker at slen - 1 + * 1 Invalid CRC + * 0 CRC OK, framing and CRC removed + */ +int hdlc_remove_framing_with_crc_check(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen); + +#ifdef __cplusplus +} +#endif + +#endif /* LIB_HDLC_H_ */ diff --git a/thirdparty/tas/tas/uart.h b/thirdparty/tas/tas/uart.h new file mode 100644 index 00000000..233a79d6 --- /dev/null +++ b/thirdparty/tas/tas/uart.h @@ -0,0 +1,124 @@ +//************************************************************************************** +/*! \copyright: 2020-2021 Thales Alenia Space Deutschland GmbH +* \project: multiMIND +* \file: (name of source file: uart.h) +* \date: (20.05.2021) +* \author: (Sarthak Kelapure) +* \brief: (UART thread to collect data on serial interface) +* \language: (C) +************************************************************************************** +*/ +#ifndef LIB_UART_H +#define LIB_UART_H + +#define BUFF_SIZE 512 +#define POLL_TIMEOUT 2000 + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + + +typedef struct serial_s serial_t; + +/** + * Destroy the serial structure + */ +void uart_destroy(serial_t* s); + +/** + * Initializes the serial connection + * @param device - serial device name. + * @param baud - baud rate for connection. + * @return serial structure. + */ +serial_t* uart_init(char device[], int baud); + +/** + * Send data. + * @param s - serial structure. + * @param data - character array to transmit. + * @param length - size of the data array. + */ +uint32_t uart_length_send(serial_t* s, uint8_t data[], int length); + +/** + * Send a single character. + * @param s - serial structure. + * @param data - single character to be sent. + */ +void uart_send(serial_t* s, uint8_t data); + +/** + * Determine how much data is available + * in the serial buffer. + * @param s - serial structure. + * @return number of characters available. + */ +int uart_available(serial_t* s); + +/** + * Fetch one char from the serial buffer. + * @param s - serial structure. + * @return character. Null if empty. + */ +char uart_get(serial_t* s); + +/** + * Fetch length of chars from the serial buffer. + * @param s - serial structure. + * @param buff - readback storage + * @param len - length to get + * @return length. zero if empty. + */ +int uart_length_get(serial_t* s, char* buff, int len, bool start_of_packet); + +uint16_t uart_get_hdlc_packet(serial_t* s, uint8_t *buff, uint16_t buff_len); + +/** + * Fetch one char from the serial buffer. + * Blocks until data becomes available. + * @param s - serial structure. + * @return character. + */ +char uart_blocking_get(serial_t* s); + +/** + * Clear the serial buffer. + * @param s - serial structure. + */ +void uart_clear(serial_t* s); + +/** + * Close the serial port. + * @param s - serial structure. + * @return value of close(). + */ +int uart_close(serial_t* s); + +/** + * Deinitializes the UART + * @param s - serial structure. + */ +void uart_deinit(serial_t* s); + +#ifdef __cplusplus +} +#endif + +#endif //LIB_UART_H diff --git a/thirdparty/tas/uart.c b/thirdparty/tas/uart.c new file mode 100644 index 00000000..11e118ed --- /dev/null +++ b/thirdparty/tas/uart.c @@ -0,0 +1,603 @@ +//************************************************************************************** +/*! \copyright: 2020-2021 Thales Alenia Space Deutschland GmbH + * \project: multiMIND + * \file: (name of source file: uart.c) + * \date: (20.05.2021) + * \author: (Sarthak Kelapure) + * \brief: (UART thread to collect data on serial interface) + * \language: (C) + ************************************************************************************** + */ + +#include "tas/uart.h" +#include "tas/hdlc.h" + +#ifdef HDLC_ENABLE +#define HDLC_RX_STATE_IDLE (0u) +#define HDLC_RX_STATE_RECEIVING (1u) +#define HDLC_RX_STATE_ESCAPE (2u) +#endif + +/** + * @struct Serial device structure. + * Encapsulates a serial connection. + */ +struct serial_s { + int fd; //>! Connection file descriptor. + int state; //>! Signifies connection state. + int running; //>! Signifies thread state. + + char rxbuff[BUFF_SIZE]; //>! Buffer for RX data. + int start, end; //>! Pointers to start and end of buffer. + + pthread_t rx_thread; //>! Listening thread. +}; + +// --------------- Internal Functions --------------- + +/** + * Connect to a serial device. + * @param s - serial structure. + * @param device - serial device name. + * @param baud - baud rate for connection. + * @return -ve on error, 0 on success. + */ +static int serial_connect(serial_t* s, char device[], int baud); + +/** + * Create the serial structure. + * Convenience method to allocate memory + * and instantiate objects. + * @return serial structure. + */ +static serial_t* serial_create(); + +static int serial_resolve_baud(int baud); + +/** + * Recieve data. + * Retrieves data from the serial device. + * @param s - serial structure. + * @param data - pointer to a buffer to read data into. + * @param maxLength - size of input buffer. + * @return amount of data recieved. + */ +static int serial_recieve(serial_t* obj, uint8_t data[], int maxLength); + +/** + * @brief Serial Listener Thread. + * This blocks waiting for data to be recieved from the serial device, + * and calls the serial_callback method with appropriate context when + * data is recieved. + * Exits when close method is called, or serial error occurs. + * @param param - context passed from thread instantiation. + */ +static void *serial_data_listener(void *param); + +/** + * @brief Start the serial threads. + * This spawns the listening and transmitting threads + * if they are not already running. + * @param s - serial structure. + * @return 0 on success, or -1 on error. + */ +static int serial_start(serial_t* s); + +/** + * Stop serial listener thread. + * @param s - serial structure. + * @return 0; + */ +static int serial_stop(serial_t* s); + +/** + * Callback to handle recieved data. + * Puts recieved data into the rx buffer. + * @param s - serial structure. + * @param data - data to be stored. + * @param length - length of recieved data. + */ +static void serial_rx_callback(serial_t* s, char data[], int length); + +// Put character in rx buffer. +static int buffer_put(serial_t* s, char c) +{ + //if there is space in the buffer + if ( s->end != ((s->start + BUFF_SIZE - 1) % BUFF_SIZE)) { + s->rxbuff[s->end] = c; + s->end ++; + s->end = s->end % BUFF_SIZE; + //printf("Put: %x start: %d, end: %d\r\n", c, s->start, s->end); + return 0; //No error + } else { + //buffer is full, this is a bad state + return -1; //Report error + } +} + +// Get character from rx buffer. +static char buffer_get(serial_t* s) +{ + char c = (char)0; + //if there is data to process + if (s->end != s->start) { + c = (s->rxbuff[s->start]); + s->start ++; + //wrap around + s->start = s->start % BUFF_SIZE; + } else { + } + //printf("Get: %x start: %d, end: %d\r\n", c, s->start, s->end); + return c; +} + +//Get data available in the rx buffer. +static int buffer_available(serial_t* s) +{ + return (s->end - s->start + BUFF_SIZE) % BUFF_SIZE; +} + +// --------------- External Functions --------------- + +//Create serial object. +serial_t* serial_create() +{ + //Allocate serial object. + serial_t* s = malloc(sizeof(serial_t)); + //Reconfigure buffer object. + s->start = 0; + s->end = 0; + //Return pointer. + return s; +} + + +void uart_destroy(serial_t* s) +{ + free(s); +} + + +//Connect to serial device. +int serial_connect(serial_t* s, char device[], int baud) +{ + struct termios oldtio; + + // Resolve baud. + int speed = serial_resolve_baud(baud); + if (speed < 0) { + printf("Error: Baud rate not recognized.\r\n"); + return -1; + } + + //Open device. + s->fd = open(device, O_RDWR | O_NOCTTY); + //Catch file open error. + if (s->fd < 0) { + perror(device); + return -2; + } + //Retrieve settings. + tcgetattr(s->fd, &oldtio); + //Set baud rate. + cfsetspeed(&oldtio, speed); + //Flush cache. + tcflush(s->fd, TCIFLUSH); + + //Set UART settings, standard ones. 8N1 + oldtio.c_cflag = (oldtio.c_cflag & ~CSIZE) | CS8; // 8-bit chars + // disable IGNBRK for mismatched speed tests; otherwise receive break + // as \000 chars + oldtio.c_iflag &= ~IGNBRK; // disable break processing + oldtio.c_lflag = 0; // no signaling chars, no echo, + // no canonical processing + oldtio.c_oflag = 0; // no remapping, no delays + oldtio.c_cc[VMIN] = 0; // read doesn't block + oldtio.c_cc[VTIME] = 5; // 0.5 seconds read timeout + + oldtio.c_iflag &= ~(IXON | IXOFF | IXANY); // shut off xon/xoff ctrl + oldtio.c_iflag &= ~(IGNCR | ICRNL | INLCR); // CR and LF characters are not affected + + oldtio.c_cflag |= (CLOCAL | CREAD);// ignore modem controls, + // enable reading + oldtio.c_cflag &= ~(PARENB | PARODD); // shut off parity + oldtio.c_cflag |= 0; + oldtio.c_cflag &= ~CSTOPB; + oldtio.c_cflag &= ~(020000000000); + //Apply settings. + if(tcsetattr(s->fd, TCSANOW, &oldtio) !=0){ + printf("ERROR: serial settings failed\r\n"); + return -1; + } + + //Start listener thread. + int res = serial_start(s); + //Catch error. + if (res < 0) { + printf("Error: serial thread could not be spawned\r\n"); + return -3; + } + + //Indicate connection was successful. + s->state = 1; + return 0; +} + +serial_t* uart_init(char device[], int baud) +{ + serial_t* s = serial_create(); + if(serial_connect(s, device, baud)< 0) + { + return NULL; + } + return s; +} + +//Send data. +uint32_t uart_length_send(serial_t* s, uint8_t data[], int length) +{ +// uint16_t ii; +// int res; +// for (ii = 0; ii < length; ii++) +// { +// res = write(s->fd, &data[ii], 1); +// } + int res = write(s->fd, data, length); + return res; +} + +void uart_send(serial_t* s, uint8_t data) +{ + char arr[1]; + arr[0] = data; + write(s->fd, arr, 1); +} + +//Determine characters available. +int uart_available(serial_t* s) +{ + return buffer_available(s); +} + +//Fetch a character. +char uart_get(serial_t* s) +{ + char c = buffer_get(s); + + return c; +} + +int uart_length_get(serial_t* s, char* buff, int len, bool start_of_packet) +{ + int ret = 0; + if (len > 0 && len < BUFF_SIZE) + { +#ifdef HDLC_ENABLE + uint8_t ch; + uint8_t hdlc_rx_state; + int rxb = 0; + + if (start_of_packet) + hdlc_rx_state = HDLC_RX_STATE_IDLE; + else + hdlc_rx_state = HDLC_RX_STATE_RECEIVING; + + while (rxb < len) + { + ch = uart_blocking_get(s); + + switch (hdlc_rx_state) + { + case HDLC_RX_STATE_IDLE: + if (ch == HDLC_START_BYTE) + { + rxb = 0; + ret = 0; + hdlc_rx_state = HDLC_RX_STATE_RECEIVING; + } + break; + case HDLC_RX_STATE_RECEIVING: + if (ch == HDLC_START_BYTE) + { + rxb = 0; + ret = 0; + break; + } + if (ch == HDLC_ESC_BYTE) + { + hdlc_rx_state = HDLC_RX_STATE_ESCAPE; + break; + } + buff[rxb++] = ch; + ret++; + break; + case HDLC_RX_STATE_ESCAPE: + if (ch == HDLC_START_BYTE) + { + rxb = 0; + ret = 0; + break; + } + buff[rxb++] = ch ^ HDLC_ESCAPE_CHAR; + ret++; + hdlc_rx_state = HDLC_RX_STATE_RECEIVING; + break; + } + } +#else + for (int i=0;i 2u) // do not include HDLC CRC16 + { + return buff_pos; + } + buff_pos = 0u; + hdlc_rx_state = HDLC_RX_STATE_IDLE; + break; + } + if (ch == HDLC_ESC_BYTE) + { + hdlc_rx_state = HDLC_RX_STATE_ESCAPE; + break; + } + if (buff_pos >= buff_len) + { + hdlc_rx_state = HDLC_RX_STATE_RECEIVING; + break; + } + buff[buff_pos++] = ch; + break; + + case HDLC_RX_STATE_ESCAPE: + if ((ch == HDLC_START_BYTE) || (ch == HDLC_END_BYTE)) + { + buff_pos = 0; + hdlc_rx_state = HDLC_RX_STATE_RECEIVING; + break; + } + if (buff_pos >= buff_len) + { + hdlc_rx_state = HDLC_RX_STATE_RECEIVING; + break; + } + buff[buff_pos++] = ch ^ HDLC_ESCAPE_CHAR; + hdlc_rx_state = HDLC_RX_STATE_RECEIVING; + break; + + default: + buff_pos = 0u; + hdlc_rx_state = HDLC_RX_STATE_IDLE; + break; + } + } +} + +char uart_blocking_get(serial_t* s) +{ + while (uart_available(s) == 0); + return uart_get(s); +} + +void uart_clear(serial_t* s) +{ + //Clear the buffer. + while (buffer_available(s)) { + buffer_get(s); + } + tcflush(s->fd, TCIFLUSH); +} + +//Close serial port. +int uart_close(serial_t* s) +{ + //Stop thread. + serial_stop(s); + return 0; +} + +void uart_deinit(serial_t* s){ + uart_clear(s); + uart_close(s); + uart_destroy(s); +} + +// --------------- Internal Functions -------------- + +//Stop serial listener thread. +static int serial_stop(serial_t* s) +{ + s->running = 0; + return close(s->fd); +} + +// Resolves standard baud rates to linux constants. +static int serial_resolve_baud(int baud) +{ + int speed; + // Switch common baud rates to temios constants. + switch (baud) { + case 9600: + speed = B9600; + break; + case 19200: + speed = B19200; + break; + case 38400: + speed = B38400; + break; + case 57600: + speed = B57600; + break; + case 115200: + speed = B115200; + break; + case 230400: + speed = B230400; + break; + case 460800: + speed = B460800; + break; + case 500000: + speed = B500000; + break; + case 576000: + speed = B576000; + break; + case 921600: + speed = B921600; + break; + case 1000000: + speed = B1000000; + break; + case 1152000: + speed = B1152000; + break; + case 1500000: + speed = B1500000; + break; + case 2000000: + speed = B2000000; + break; + case 3000000: + speed = B3000000; + break; + default: + speed = -1; + break; + } + // Return. + return speed; +} + +// Start serial listener. +static int serial_start(serial_t* s) +{ + //Only start if it is not currently running. + if (s->running != 1) { + //Set running. + s->running = 1; + //Spawn thread. + int res; + res = pthread_create(&s->rx_thread, NULL, serial_data_listener, (void*) s); + if (res != 0) { + return -2; + } + //Return result. + return 0; + } else { + return -1; + } +} + + + +//Recieve data. +static int serial_recieve(serial_t* s, uint8_t data[], int maxLength) +{ + return read(s->fd, data, maxLength); +} + +//Callback to store data in buffer. +static void serial_rx_callback(serial_t* s, char data[], int length) +{ + //Put data into buffer. + int i; + //Put data into buffer. + for (i = 0; i < length; i++) { + buffer_put(s, data[i]); + } + +} + +//Serial data listener thread. +static void *serial_data_listener(void *param) +{ + int res = 0; + int err = 0; + struct pollfd ufds; + uint8_t buff[BUFF_SIZE]; + + //Retrieve paramaters and store locally. + serial_t* serial = (serial_t*) param; + int fd = serial->fd; + + //Set up poll file descriptors. + ufds.fd = fd; //Attach socket to watch. + ufds.events = POLLIN; //Set events to notify on. + + //Run until ended. + while (serial->running != 0) { + //Poll socket for data. + res = poll(&ufds, 1, POLL_TIMEOUT); + //If data was recieved. + if (res > 0) { + //Fetch the data. + int count = serial_recieve(serial, buff, BUFF_SIZE - 1); + //If data was recieved. + if (count > 0) { + //Pad end of buffer to ensure there is a termination symbol. + buff[count] = '\0'; + // Call the serial callback. + serial_rx_callback(serial, (char *)buff, count); + //If an error occured. + } else if (count < 0) { + //Inform user and exit thread. + printf("Error: Serial disconnect\r\n"); + err = 1; + break; + } + //If there was an error. + } else if (res < 0) { + //Inform user and exit thread. + printf("Error: Polling error in serial thread"); + err = 1; + break; + } + //Otherwise, keep going around. + } + //If there was an error, close socket. + if (err) { + uart_close(serial); + //raise(SIGLOST); + } + //Close file. + res = close(serial->fd); + + return NULL; +} diff --git a/tmtc b/tmtc index 9cd4846d..12f7b5bb 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 9cd4846d396373325fc5e03a367fed236dfc16d7 +Subproject commit 12f7b5bb258f183b62a2ed27776d2385a728306e