From 0697cca88a4881e3c980528251293cb8237fd9ad Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 25 Apr 2022 13:36:11 +0200 Subject: [PATCH 001/176] started acs subsystem --- bsp_q7s/core/ObjectFactory.cpp | 4 +- common/config/commonObjects.h | 8 +- generators/fsfwgen | 2 +- mission/system/objects/definitions.h | 6 ++ mission/system/tree/CMakeLists.txt | 2 + mission/system/tree/acsModeTree.cpp | 26 ++++-- mission/system/tree/acsModeTree.h | 4 +- mission/system/tree/payloadModeTree.cpp | 116 ++++++++++++++++++++++++ mission/system/tree/payloadModeTree.h | 12 +++ mission/system/tree/system.cpp | 9 ++ mission/system/tree/system.h | 10 ++ 11 files changed, 183 insertions(+), 16 deletions(-) create mode 100644 mission/system/tree/payloadModeTree.cpp create mode 100644 mission/system/tree/payloadModeTree.h create mode 100644 mission/system/tree/system.cpp create mode 100644 mission/system/tree/system.h diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index 19457188..9489dbc3 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -42,7 +42,7 @@ #include "mission/system/objects/SusAssembly.h" #include "mission/system/objects/SusFdir.h" #include "mission/system/objects/TcsBoardAssembly.h" -#include "mission/system/tree/acsModeTree.h" +#include "mission/system/tree/system.h" #include "tmtc/apid.h" #include "tmtc/pusIds.h" @@ -208,7 +208,7 @@ void ObjectFactory::produce(void* args) { new PlocUpdater(objects::PLOC_UPDATER); new PlocMemoryDumper(objects::PLOC_MEMORY_DUMPER); - satsystem::initAcsSubsystem(); + satsystem::init(); } void ObjectFactory::createTmpComponents() { diff --git a/common/config/commonObjects.h b/common/config/commonObjects.h index 0b27a023..fff9b465 100644 --- a/common/config/commonObjects.h +++ b/common/config/commonObjects.h @@ -38,7 +38,7 @@ enum commonObjects: uint32_t { GYRO_2_ADIS_HANDLER = 0x44120212, GYRO_3_L3G_HANDLER = 0x44120313, PLPCDU_HANDLER = 0x44300000, - + SCEX_HANDLER = 0x44400000, IMTQ_HANDLER = 0x44140014, PLOC_MPSOC_HANDLER = 0x44330015, PLOC_SUPERVISOR_HANDLER = 0x44330016, @@ -99,8 +99,12 @@ enum commonObjects: uint32_t { SUS_BOARD_ASS = 0x73000002, TCS_BOARD_ASS = 0x73000003, RW_ASS = 0x73000004, - ACS_SUBSYSTEM = 0x73010001, + PLOC_SWITCHER = 0x73000005, + CAM_SWITCHER = 0x73000006, EIVE_SYSTEM = 0x73010000, + ACS_SUBSYSTEM = 0x73010001, + PL_SUBSYSTEM = 0x73010002, + PLOC_SUBSYSTEM = 0x73010003, }; } diff --git a/generators/fsfwgen b/generators/fsfwgen index d2bdabbf..2a408e8c 160000 --- a/generators/fsfwgen +++ b/generators/fsfwgen @@ -1 +1 @@ -Subproject commit d2bdabbf0f213747efc18cb45fcf2a2294b14bc8 +Subproject commit 2a408e8c7dd2ebe974b9699fb5aee0889aa86392 diff --git a/mission/system/objects/definitions.h b/mission/system/objects/definitions.h index aee127bb..99868659 100644 --- a/mission/system/objects/definitions.h +++ b/mission/system/objects/definitions.h @@ -16,4 +16,10 @@ enum Submodes : Submode_t { A_SIDE = 0, B_SIDE = 1, DUAL_MODE = 2 }; } // namespace duallane +namespace payload { + +enum Modes { NONE = 0, DAC = 1, CAM = 2, PL_DATA = 3, EARTH_OBSV = 4, SCEX = 5 }; + +} + #endif /* MISSION_SYSTEM_DEFINITIONS_H_ */ diff --git a/mission/system/tree/CMakeLists.txt b/mission/system/tree/CMakeLists.txt index f88891d4..c5bddc3f 100644 --- a/mission/system/tree/CMakeLists.txt +++ b/mission/system/tree/CMakeLists.txt @@ -1,3 +1,5 @@ target_sources(${LIB_EIVE_MISSION} PRIVATE acsModeTree.cpp + payloadModeTree.cpp + system.cpp ) diff --git a/mission/system/tree/acsModeTree.cpp b/mission/system/tree/acsModeTree.cpp index e5748f08..3fca1ce0 100644 --- a/mission/system/tree/acsModeTree.cpp +++ b/mission/system/tree/acsModeTree.cpp @@ -8,6 +8,8 @@ #include "mission/controller/controllerdefinitions/AcsControllerDefinitions.h" +// Alias for checker function +namespace { void checkInsert(ReturnValue_t result, const char* ctx); void buildOffSequence(Subsystem* ss, ModeListEntry& eh); void buildDetumbleSequence(Subsystem* ss, ModeListEntry& entryHelper); @@ -15,8 +17,8 @@ void buildSafeSequence(Subsystem* ss, ModeListEntry& entryHelper); void buildIdleSequence(Subsystem* ss, ModeListEntry& entryHelper); void buildIdleChargeSequence(Subsystem* ss, ModeListEntry& entryHelper); void buildTargetPtSequence(Subsystem* ss, ModeListEntry& entryHelper); +} // namespace -// Alias for checker function const auto CHK = checkInsert; static const auto OFF = HasModesIF::MODE_OFF; static const auto NML = DeviceHandlerIF::MODE_NORMAL; @@ -73,7 +75,7 @@ auto ACS_TABLE_TARGET_PT_TRANS_0 = auto ACS_TABLE_TARGET_PT_TRANS_1 = std::make_pair((acs::CtrlModes::TARGET_PT << 24) | 3, FixedArrayList()); -void satsystem::initAcsSubsystem() { +void satsystem::acs::init() { ModeListEntry entry; Subsystem* acsSubsystem = new Subsystem(objects::ACS_SUBSYSTEM, objects::EIVE_SYSTEM, 12, 24); buildOffSequence(acsSubsystem, entry); @@ -82,11 +84,13 @@ void satsystem::initAcsSubsystem() { buildIdleSequence(acsSubsystem, entry); buildIdleChargeSequence(acsSubsystem, entry); buildTargetPtSequence(acsSubsystem, entry); - acsSubsystem->setInitialMode(HasModesIF::MODE_OFF); + acsSubsystem->setInitialMode(OFF); } +namespace { + void buildOffSequence(Subsystem* ss, ModeListEntry& eh) { - std::string context = "satsystem::buildOffSequence"; + std::string context = "satsystem::acs::buildOffSequence"; auto ctxc = context.c_str(); // Insert Helper Table auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, ArrayList& table) { @@ -125,7 +129,7 @@ void buildOffSequence(Subsystem* ss, ModeListEntry& eh) { } void buildSafeSequence(Subsystem* ss, ModeListEntry& eh) { - std::string context = "satsystem::buildSafeSequence"; + std::string context = "satsystem::acs::buildSafeSequence"; auto ctxc = context.c_str(); // Insert Helper Table auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, @@ -174,7 +178,7 @@ void buildSafeSequence(Subsystem* ss, ModeListEntry& eh) { } void buildDetumbleSequence(Subsystem* ss, ModeListEntry& eh) { - std::string context = "satsystem::buildDetumbleSequence"; + std::string context = "satsystem::acs::buildDetumbleSequence"; auto ctxc = context.c_str(); // Insert Helper Table auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, @@ -226,7 +230,7 @@ void buildDetumbleSequence(Subsystem* ss, ModeListEntry& eh) { } void buildIdleSequence(Subsystem* ss, ModeListEntry& eh) { - std::string context = "satsystem::buildIdleSequence"; + std::string context = "satsystem::acs::buildIdleSequence"; auto ctxc = context.c_str(); // Insert Helper Table auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, @@ -273,7 +277,7 @@ void buildIdleSequence(Subsystem* ss, ModeListEntry& eh) { } void buildIdleChargeSequence(Subsystem* ss, ModeListEntry& eh) { - std::string context = "satsystem::buildIdleChargeSequence"; + std::string context = "satsystem::acs::buildIdleChargeSequence"; auto ctxc = context.c_str(); // Insert Helper Table auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, @@ -327,7 +331,7 @@ void buildIdleChargeSequence(Subsystem* ss, ModeListEntry& eh) { } void buildTargetPtSequence(Subsystem* ss, ModeListEntry& eh) { - std::string context = "satsystem::buildTargetPtSequence"; + std::string context = "satsystem::acs::buildTargetPtSequence"; auto ctxc = context.c_str(); // Insert Helper Table auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, @@ -383,6 +387,8 @@ void buildTargetPtSequence(Subsystem* ss, ModeListEntry& eh) { void checkInsert(ReturnValue_t result, const char* ctx) { if (result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "satsystem::checkInsert: Insertion failed at " << ctx << std::endl; + sif::warning << "Insertion failed at " << ctx << std::endl; } } + +} // namespace diff --git a/mission/system/tree/acsModeTree.h b/mission/system/tree/acsModeTree.h index 5ad5d7c9..3492ee9e 100644 --- a/mission/system/tree/acsModeTree.h +++ b/mission/system/tree/acsModeTree.h @@ -3,7 +3,9 @@ class Subsystem; namespace satsystem { +namespace acs { -void initAcsSubsystem(); +void init(); +} } // namespace satsystem diff --git a/mission/system/tree/payloadModeTree.cpp b/mission/system/tree/payloadModeTree.cpp new file mode 100644 index 00000000..8d5ff876 --- /dev/null +++ b/mission/system/tree/payloadModeTree.cpp @@ -0,0 +1,116 @@ +#include "payloadModeTree.h" + +#include +#include +#include +#include +#include + +#include "mission/system/objects/PayloadSubsystem.h" + +namespace { +void checkInsert(ReturnValue_t result, const char* ctx); +void initOffSequence(Subsystem* ss, ModeListEntry& eh); +void initPlDacSequence(Subsystem* ss, ModeListEntry& eh); +void initPlCamSequence(Subsystem* ss, ModeListEntry& eh); +void initPlDataSequence(Subsystem* ss, ModeListEntry& eh); +void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh); +void initScexSequence(Subsystem* ss, ModeListEntry& eh); +} // namespace + +const auto CHK = checkInsert; +static const auto OFF = HasModesIF::MODE_OFF; +// static const auto NML = DeviceHandlerIF::MODE_NORMAL; + +auto PL_SEQUENCE_OFF = std::make_pair(OFF << 24, FixedArrayList()); +auto PL_TABLE_OFF_TGT = std::make_pair((OFF << 24) | 1, FixedArrayList()); +auto PL_TABLE_OFF_TRANS = std::make_pair((OFF << 24) | 2, FixedArrayList()); + +void satsystem::pl::init() { + ModeListEntry entry; + Subsystem* plSubsystem = new Subsystem(objects::PL_SUBSYSTEM, objects::EIVE_SYSTEM, 12, 24); + initOffSequence(plSubsystem, entry); + initPlDacSequence(plSubsystem, entry); + initPlCamSequence(plSubsystem, entry); + initPlDataSequence(plSubsystem, entry); + initEarthObsvSequence(plSubsystem, entry); + initScexSequence(plSubsystem, entry); + plSubsystem->setInitialMode(OFF); +} + +namespace { + +void initOffSequence(Subsystem* ss, ModeListEntry& eh) { + std::string context = "satsystem::payload::buildOffSequence"; + auto ctxc = context.c_str(); + // Insert Helper Table + auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, + ArrayList& sequence) { + eh.setObject(obj); + eh.setMode(mode); + eh.setSubmode(submode); + CHK(sequence.insert(eh), ctxc); + }; + // Insert Helper Sequence + auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, + bool checkSuccess) { + eh.setTableId(tableId); + eh.setWaitSeconds(waitSeconds); + eh.setCheckSuccess(checkSuccess); + CHK(sequence.insert(eh), ctxc); + }; + + // Build OFF target. Is empty + ss->addTable(&PL_TABLE_OFF_TGT.second, PL_TABLE_OFF_TGT.first, false, true); + + // Build OFF transition 0 + iht(objects::PLOC_SWITCHER, OFF, 0, PL_TABLE_OFF_TRANS.second); + iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_OFF_TRANS.second); + iht(objects::SCEX_HANDLER, OFF, 0, PL_TABLE_OFF_TRANS.second); + iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_OFF_TRANS.second); + iht(objects::PLOC_SUBSYSTEM, OFF, 0, PL_TABLE_OFF_TRANS.second); + ss->addTable(&PL_TABLE_OFF_TRANS.second, PL_TABLE_OFF_TRANS.first, false, true); + + // Build OFF sequence + ihs(PL_SEQUENCE_OFF.second, PL_TABLE_OFF_TGT.first, 0, false); + ihs(PL_SEQUENCE_OFF.second, PL_TABLE_OFF_TRANS.first, 0, false); + ss->addSequence(&PL_SEQUENCE_OFF.second, PL_SEQUENCE_OFF.first, PL_SEQUENCE_OFF.first, false, + true); +} + +void initPlDacSequence(Subsystem* ss, ModeListEntry& eh) { + std::string context = "satsystem::payload::initPlDacSequence"; + auto ctxc = context.c_str(); + // Insert Helper Table + auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, + ArrayList& sequence) { + eh.setObject(obj); + eh.setMode(mode); + eh.setSubmode(submode); + CHK(sequence.insert(eh), ctxc); + }; + // Insert Helper Sequence + auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, + bool checkSuccess) { + eh.setTableId(tableId); + eh.setWaitSeconds(waitSeconds); + eh.setCheckSuccess(checkSuccess); + CHK(sequence.insert(eh), ctxc); + }; +} + +void initPlCamSequence(Subsystem* ss, ModeListEntry& eh) {} + +void initPlDataSequence(Subsystem* ss, ModeListEntry& eh) {} + +void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh) {} + +void initScexSequence(Subsystem* ss, ModeListEntry& eh) {} + +void checkInsert(ReturnValue_t result, const char* ctx) { + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "satsystem::checkInsert: PL | Insertion failed at " << ctx << std::endl; + } +} + +} // namespace diff --git a/mission/system/tree/payloadModeTree.h b/mission/system/tree/payloadModeTree.h new file mode 100644 index 00000000..738eb01c --- /dev/null +++ b/mission/system/tree/payloadModeTree.h @@ -0,0 +1,12 @@ +#ifndef MISSION_SYSTEM_TREE_PAYLOADMODETREE_H_ +#define MISSION_SYSTEM_TREE_PAYLOADMODETREE_H_ + +namespace satsystem { + +namespace pl { +void init(); +} + +} // namespace satsystem + +#endif /* MISSION_SYSTEM_TREE_PAYLOADMODETREE_H_ */ diff --git a/mission/system/tree/system.cpp b/mission/system/tree/system.cpp new file mode 100644 index 00000000..4455588f --- /dev/null +++ b/mission/system/tree/system.cpp @@ -0,0 +1,9 @@ +#include "system.h" + +#include "acsModeTree.h" +#include "payloadModeTree.h" + +void satsystem::init() { + acs::init(); + pl::init(); +} diff --git a/mission/system/tree/system.h b/mission/system/tree/system.h new file mode 100644 index 00000000..a8599121 --- /dev/null +++ b/mission/system/tree/system.h @@ -0,0 +1,10 @@ +#ifndef MISSION_SYSTEM_TREE_SYSTEM_H_ +#define MISSION_SYSTEM_TREE_SYSTEM_H_ + +namespace satsystem { + +void init(); + +} + +#endif /* MISSION_SYSTEM_TREE_SYSTEM_H_ */ From f5723dc1816263d2a28cf8257afeb670c63ffd49 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 25 Apr 2022 18:44:38 +0200 Subject: [PATCH 002/176] continued pl ss --- .../payloadPcduDefinitions.h | 3 + mission/system/objects/definitions.h | 8 +- mission/system/tree/payloadModeTree.cpp | 157 ++++++++++++++++-- 3 files changed, 156 insertions(+), 12 deletions(-) diff --git a/mission/devices/devicedefinitions/payloadPcduDefinitions.h b/mission/devices/devicedefinitions/payloadPcduDefinitions.h index ab387fc7..6ad31d3f 100644 --- a/mission/devices/devicedefinitions/payloadPcduDefinitions.h +++ b/mission/devices/devicedefinitions/payloadPcduDefinitions.h @@ -101,6 +101,9 @@ enum NormalSubmodeBits { }; static constexpr Submode_t ALL_OFF_SUBMODE = 0; +static constexpr Submode_t ALL_ON_SUBMODE = (1 << HPA_ON) | (1 << MPA_ON) | (1 << TX_ON) | + (1 << X8_ON) | (1 << DRO_ON) | + (1 << SOLID_STATE_RELAYS_ADC_ON); // 12 ADC values * 2 + trailing zero static constexpr size_t ADC_REPLY_SIZE = 25; diff --git a/mission/system/objects/definitions.h b/mission/system/objects/definitions.h index 99868659..99fc5eb6 100644 --- a/mission/system/objects/definitions.h +++ b/mission/system/objects/definitions.h @@ -18,8 +18,14 @@ enum Submodes : Submode_t { A_SIDE = 0, B_SIDE = 1, DUAL_MODE = 2 }; namespace payload { -enum Modes { NONE = 0, DAC = 1, CAM = 2, PL_DATA = 3, EARTH_OBSV = 4, SCEX = 5 }; +enum Modes { NONE = 0, SUPV_ONLY = 1, MPSOC_STREAM = 2, CAM_STREAM = 3, EARTH_OBSV = 4, SCEX = 5 }; + +namespace ploc { + +enum Modes { OFF = 0, SUPV_ONLY = 1, MPSOC_ON = 2 }; } +} // namespace payload + #endif /* MISSION_SYSTEM_DEFINITIONS_H_ */ diff --git a/mission/system/tree/payloadModeTree.cpp b/mission/system/tree/payloadModeTree.cpp index 8d5ff876..2ce4678a 100644 --- a/mission/system/tree/payloadModeTree.cpp +++ b/mission/system/tree/payloadModeTree.cpp @@ -6,33 +6,63 @@ #include #include +#include "mission/devices/devicedefinitions/payloadPcduDefinitions.h" #include "mission/system/objects/PayloadSubsystem.h" +#include "mission/system/objects/definitions.h" namespace { void checkInsert(ReturnValue_t result, const char* ctx); void initOffSequence(Subsystem* ss, ModeListEntry& eh); -void initPlDacSequence(Subsystem* ss, ModeListEntry& eh); -void initPlCamSequence(Subsystem* ss, ModeListEntry& eh); -void initPlDataSequence(Subsystem* ss, ModeListEntry& eh); +void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh); +void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh); +void initPlSpvSequence(Subsystem* ss, ModeListEntry& eh); void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh); void initScexSequence(Subsystem* ss, ModeListEntry& eh); } // namespace const auto CHK = checkInsert; static const auto OFF = HasModesIF::MODE_OFF; -// static const auto NML = DeviceHandlerIF::MODE_NORMAL; +static const auto ON = HasModesIF::MODE_ON; +static const auto NML = DeviceHandlerIF::MODE_NORMAL; auto PL_SEQUENCE_OFF = std::make_pair(OFF << 24, FixedArrayList()); auto PL_TABLE_OFF_TGT = std::make_pair((OFF << 24) | 1, FixedArrayList()); auto PL_TABLE_OFF_TRANS = std::make_pair((OFF << 24) | 2, FixedArrayList()); +auto PL_SEQUENCE_MPSOC_STREAM = + std::make_pair(payload::Modes::MPSOC_STREAM << 24, FixedArrayList()); +auto PL_TABLE_MPSOC_STREAM_TGT = + std::make_pair((payload::Modes::MPSOC_STREAM << 24) | 1, FixedArrayList()); +auto PL_TABLE_MPSOC_STREAM_TRANS_0 = + std::make_pair((payload::Modes::MPSOC_STREAM << 24) | 2, FixedArrayList()); +auto PL_TABLE_MPSOC_STREAM_TRANS_1 = + std::make_pair((payload::Modes::MPSOC_STREAM << 24) | 2, FixedArrayList()); + +auto PL_SEQUENCE_CAM_STREAM = + std::make_pair(payload::Modes::CAM_STREAM << 24, FixedArrayList()); +auto PL_TABLE_CAM_STREAM_TGT = + std::make_pair((payload::Modes::CAM_STREAM << 24) | 1, FixedArrayList()); +auto PL_TABLE_CAM_STREAM_TRANS_0 = + std::make_pair((payload::Modes::CAM_STREAM << 24) | 2, FixedArrayList()); +auto PL_TABLE_CAM_STREAM_TRANS_1 = + std::make_pair((payload::Modes::CAM_STREAM << 24) | 2, FixedArrayList()); + +auto PL_SEQUENCE_SUPV_ONLY = + std::make_pair(payload::Modes::CAM_STREAM << 24, FixedArrayList()); +auto PL_TABLE_SUPV_ONLY_TGT = + std::make_pair((payload::Modes::CAM_STREAM << 24) | 1, FixedArrayList()); +auto PL_TABLE_SUPV_ONLY_TRANS_0 = + std::make_pair((payload::Modes::CAM_STREAM << 24) | 2, FixedArrayList()); +auto PL_TABLE_SUPV_ONLY_TRANS_1 = + std::make_pair((payload::Modes::CAM_STREAM << 24) | 2, FixedArrayList()); + void satsystem::pl::init() { ModeListEntry entry; Subsystem* plSubsystem = new Subsystem(objects::PL_SUBSYSTEM, objects::EIVE_SYSTEM, 12, 24); initOffSequence(plSubsystem, entry); - initPlDacSequence(plSubsystem, entry); - initPlCamSequence(plSubsystem, entry); - initPlDataSequence(plSubsystem, entry); + initPlMpsocStreamSequence(plSubsystem, entry); + initPlCamStreamSequence(plSubsystem, entry); + initPlSpvSequence(plSubsystem, entry); initEarthObsvSequence(plSubsystem, entry); initScexSequence(plSubsystem, entry); plSubsystem->setInitialMode(OFF); @@ -78,8 +108,8 @@ void initOffSequence(Subsystem* ss, ModeListEntry& eh) { true); } -void initPlDacSequence(Subsystem* ss, ModeListEntry& eh) { - std::string context = "satsystem::payload::initPlDacSequence"; +void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh) { + std::string context = "satsystem::payload::initPlMpsocStreamSequence"; auto ctxc = context.c_str(); // Insert Helper Table auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, @@ -97,11 +127,116 @@ void initPlDacSequence(Subsystem* ss, ModeListEntry& eh) { eh.setCheckSuccess(checkSuccess); CHK(sequence.insert(eh), ctxc); }; + + // Build MPSoC stream target + // Camera should always be off to prevent a conflict with the MPSoC streaming + iht(objects::PLPCDU_HANDLER, NML, plpcdu::ALL_ON_SUBMODE, PL_TABLE_MPSOC_STREAM_TGT.second); + iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_MPSOC_STREAM_TGT.second); + iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_MPSOC_STREAM_TGT.second); + iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::MPSOC_ON, PL_TABLE_MPSOC_STREAM_TGT.second); + ss->addTable(&PL_TABLE_MPSOC_STREAM_TGT.second, PL_TABLE_MPSOC_STREAM_TGT.first, false, true); + + // Build MPSoC stream transition 0 + iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); + iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); + iht(objects::SCEX_HANDLER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); + ss->addTable(&PL_TABLE_MPSOC_STREAM_TRANS_0.second, PL_TABLE_MPSOC_STREAM_TRANS_0.first, false, + true); + + // Build MPSoC stream transition 1 + iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::MPSOC_ON, PL_TABLE_MPSOC_STREAM_TRANS_1.second); + ss->addTable(&PL_TABLE_MPSOC_STREAM_TRANS_1.second, PL_TABLE_MPSOC_STREAM_TRANS_1.first, false, + true); + + // Build MPSoC stream sequence + ihs(PL_SEQUENCE_MPSOC_STREAM.second, PL_TABLE_MPSOC_STREAM_TGT.first, 0, true); + ihs(PL_SEQUENCE_MPSOC_STREAM.second, PL_TABLE_MPSOC_STREAM_TRANS_0.first, 0, true); + ihs(PL_SEQUENCE_MPSOC_STREAM.second, PL_TABLE_MPSOC_STREAM_TRANS_1.first, 0, false); + ss->addSequence(&PL_SEQUENCE_MPSOC_STREAM.second, PL_SEQUENCE_MPSOC_STREAM.first, + PL_SEQUENCE_OFF.first, false, true); } -void initPlCamSequence(Subsystem* ss, ModeListEntry& eh) {} +void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh) { + std::string context = "satsystem::payload::initPlCamSequence"; + auto ctxc = context.c_str(); + // Insert Helper Table + auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, + ArrayList& sequence) { + eh.setObject(obj); + eh.setMode(mode); + eh.setSubmode(submode); + CHK(sequence.insert(eh), ctxc); + }; + // Insert Helper Sequence + auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, + bool checkSuccess) { + eh.setTableId(tableId); + eh.setWaitSeconds(waitSeconds); + eh.setCheckSuccess(checkSuccess); + CHK(sequence.insert(eh), ctxc); + }; -void initPlDataSequence(Subsystem* ss, ModeListEntry& eh) {} + // Build CAM target + // Only check that the PL PCDU is on for now. It might later become necessary to switch on + // the PLOC, so we ignore its state. + iht(objects::PLPCDU_HANDLER, NML, plpcdu::ALL_ON_SUBMODE, PL_TABLE_CAM_STREAM_TGT.second); + ss->addTable(&PL_TABLE_CAM_STREAM_TGT.second, PL_TABLE_CAM_STREAM_TGT.first, false, true); + + // Build CAM transition 0 + // PLOC is actively commanded off here + iht(objects::PLOC_SUBSYSTEM, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); + iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); + iht(objects::SCEX_HANDLER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); + ss->addTable(&PL_TABLE_MPSOC_STREAM_TRANS_0.second, PL_TABLE_MPSOC_STREAM_TRANS_0.first, false, + true); + + // Build CAM transition 1 + iht(objects::PLOC_SWITCHER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_1.second); + ss->addTable(&PL_TABLE_MPSOC_STREAM_TRANS_1.second, PL_TABLE_MPSOC_STREAM_TRANS_1.first, false, + true); + + // Build CAM stream sequence + ihs(PL_SEQUENCE_CAM_STREAM.second, PL_TABLE_CAM_STREAM_TGT.first, 0, true); + ihs(PL_SEQUENCE_CAM_STREAM.second, PL_TABLE_CAM_STREAM_TRANS_0.first, 0, true); + ihs(PL_SEQUENCE_CAM_STREAM.second, PL_TABLE_CAM_STREAM_TRANS_1.first, 0, false); + ss->addSequence(&PL_SEQUENCE_CAM_STREAM.second, PL_SEQUENCE_CAM_STREAM.first, + PL_SEQUENCE_OFF.first, false, true); +} + +void initPlSpvSequence(Subsystem* ss, ModeListEntry& eh) { + std::string context = "satsystem::payload::initPlSupvSequence"; + auto ctxc = context.c_str(); + // Insert Helper Table + auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, + ArrayList& sequence) { + eh.setObject(obj); + eh.setMode(mode); + eh.setSubmode(submode); + CHK(sequence.insert(eh), ctxc); + }; + // Insert Helper Sequence + auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, + bool checkSuccess) { + eh.setTableId(tableId); + eh.setWaitSeconds(waitSeconds); + eh.setCheckSuccess(checkSuccess); + CHK(sequence.insert(eh), ctxc); + }; + + // Build Payload Supervisor Only target + iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_SUPV_ONLY_TGT.second); + iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::SUPV_ONLY, PL_TABLE_SUPV_ONLY_TGT.second); + ss->addTable(&PL_TABLE_SUPV_ONLY_TGT.second, PL_TABLE_SUPV_ONLY_TGT.first, false, true); + + // Build Payload Supervisor Only transition 0 + iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_SUPV_ONLY_TRANS_0.second); + ss->addTable(&PL_TABLE_SUPV_ONLY_TRANS_0.second, PL_TABLE_SUPV_ONLY_TRANS_0.first, inStore, + preInit) + + // Build Payload Supervisor Only transition 1 + iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::SUPV_ONLY, + PL_TABLE_SUPV_ONLY_TRANS_1.second); +} void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh) {} From c1fe7563d2b50945831be6827a4eb7dbead614d6 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 28 Apr 2022 15:05:38 +0200 Subject: [PATCH 003/176] finished first rudimentary pl ss --- fsfw | 2 +- mission/system/tree/payloadModeTree.cpp | 129 +++++++++++++++++++++--- 2 files changed, 114 insertions(+), 17 deletions(-) diff --git a/fsfw b/fsfw index d61fe7db..1c4ea6dd 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit d61fe7db93b37dd6652dbfee5b7c93f400ac5a11 +Subproject commit 1c4ea6dd0dbc6e93086c28d8e0ce3bed5be0c73c diff --git a/mission/system/tree/payloadModeTree.cpp b/mission/system/tree/payloadModeTree.cpp index 2ce4678a..ad65230f 100644 --- a/mission/system/tree/payloadModeTree.cpp +++ b/mission/system/tree/payloadModeTree.cpp @@ -36,25 +36,41 @@ auto PL_TABLE_MPSOC_STREAM_TGT = auto PL_TABLE_MPSOC_STREAM_TRANS_0 = std::make_pair((payload::Modes::MPSOC_STREAM << 24) | 2, FixedArrayList()); auto PL_TABLE_MPSOC_STREAM_TRANS_1 = - std::make_pair((payload::Modes::MPSOC_STREAM << 24) | 2, FixedArrayList()); + std::make_pair((payload::Modes::MPSOC_STREAM << 24) | 3, FixedArrayList()); auto PL_SEQUENCE_CAM_STREAM = std::make_pair(payload::Modes::CAM_STREAM << 24, FixedArrayList()); auto PL_TABLE_CAM_STREAM_TGT = - std::make_pair((payload::Modes::CAM_STREAM << 24) | 1, FixedArrayList()); + std::make_pair((payload::Modes::CAM_STREAM << 24) | 1, FixedArrayList()); auto PL_TABLE_CAM_STREAM_TRANS_0 = - std::make_pair((payload::Modes::CAM_STREAM << 24) | 2, FixedArrayList()); -auto PL_TABLE_CAM_STREAM_TRANS_1 = std::make_pair((payload::Modes::CAM_STREAM << 24) | 2, FixedArrayList()); +auto PL_TABLE_CAM_STREAM_TRANS_1 = + std::make_pair((payload::Modes::CAM_STREAM << 24) | 3, FixedArrayList()); auto PL_SEQUENCE_SUPV_ONLY = - std::make_pair(payload::Modes::CAM_STREAM << 24, FixedArrayList()); + std::make_pair(payload::Modes::SUPV_ONLY << 24, FixedArrayList()); auto PL_TABLE_SUPV_ONLY_TGT = - std::make_pair((payload::Modes::CAM_STREAM << 24) | 1, FixedArrayList()); + std::make_pair((payload::Modes::SUPV_ONLY << 24) | 1, FixedArrayList()); auto PL_TABLE_SUPV_ONLY_TRANS_0 = - std::make_pair((payload::Modes::CAM_STREAM << 24) | 2, FixedArrayList()); + std::make_pair((payload::Modes::SUPV_ONLY << 24) | 2, FixedArrayList()); auto PL_TABLE_SUPV_ONLY_TRANS_1 = - std::make_pair((payload::Modes::CAM_STREAM << 24) | 2, FixedArrayList()); + std::make_pair((payload::Modes::SUPV_ONLY << 24) | 3, FixedArrayList()); + +auto PL_SEQUENCE_EARTH_OBSV = + std::make_pair(payload::Modes::EARTH_OBSV << 24, FixedArrayList()); +auto PL_TABLE_EARTH_OBSV_TGT = + std::make_pair((payload::Modes::EARTH_OBSV << 24) | 1, FixedArrayList()); +auto PL_TABLE_EARTH_OBSV_TRANS_0 = + std::make_pair((payload::Modes::EARTH_OBSV << 24) | 2, FixedArrayList()); +auto PL_TABLE_EARTH_OBSV_TRANS_1 = + std::make_pair((payload::Modes::EARTH_OBSV << 24) | 3, FixedArrayList()); + +auto PL_SEQUENCE_SCEX = + std::make_pair(payload::Modes::SCEX << 24, FixedArrayList()); +auto PL_TABLE_SCEX_TGT = + std::make_pair((payload::Modes::SCEX << 24) | 1, FixedArrayList()); +auto PL_TABLE_SCEX_TRANS_0 = + std::make_pair((payload::Modes::SCEX << 24) | 2, FixedArrayList()); void satsystem::pl::init() { ModeListEntry entry; @@ -226,21 +242,102 @@ void initPlSpvSequence(Subsystem* ss, ModeListEntry& eh) { // Build Payload Supervisor Only target iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_SUPV_ONLY_TGT.second); iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::SUPV_ONLY, PL_TABLE_SUPV_ONLY_TGT.second); - ss->addTable(&PL_TABLE_SUPV_ONLY_TGT.second, PL_TABLE_SUPV_ONLY_TGT.first, false, true); + ss->addTable(TableEntry(PL_TABLE_SUPV_ONLY_TGT.first, &PL_TABLE_SUPV_ONLY_TGT.second)); // Build Payload Supervisor Only transition 0 iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_SUPV_ONLY_TRANS_0.second); - ss->addTable(&PL_TABLE_SUPV_ONLY_TRANS_0.second, PL_TABLE_SUPV_ONLY_TRANS_0.first, inStore, - preInit) + iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_SUPV_ONLY_TRANS_0.second); + ss->addTable(TableEntry(PL_TABLE_SUPV_ONLY_TRANS_0.first, &PL_TABLE_SUPV_ONLY_TRANS_0.second)); - // Build Payload Supervisor Only transition 1 - iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::SUPV_ONLY, - PL_TABLE_SUPV_ONLY_TRANS_1.second); + // Build Payload Supervisor Only transition 1 + iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::SUPV_ONLY, PL_TABLE_SUPV_ONLY_TRANS_1.second); + + // Build Payload Supervisor Only Sequence + ihs(PL_SEQUENCE_SUPV_ONLY.second, PL_TABLE_SUPV_ONLY_TGT.first, 0, true); + ihs(PL_SEQUENCE_SUPV_ONLY.second, PL_TABLE_SUPV_ONLY_TRANS_0.first, 0, true); + ihs(PL_SEQUENCE_SUPV_ONLY.second, PL_TABLE_SUPV_ONLY_TRANS_1.first, 0, false); + ss->addSequence(SequenceEntry(PL_SEQUENCE_SUPV_ONLY.first, &PL_SEQUENCE_SUPV_ONLY.second, + PL_SEQUENCE_OFF.first)); } -void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh) {} +void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh) { + std::string context = "satsystem::payload::initEarthObsvSequence"; + auto ctxc = context.c_str(); + // Insert Helper Table + auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, + ArrayList& sequence) { + eh.setObject(obj); + eh.setMode(mode); + eh.setSubmode(submode); + CHK(sequence.insert(eh), ctxc); + }; + // Insert Helper Sequence + auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, + bool checkSuccess) { + eh.setTableId(tableId); + eh.setWaitSeconds(waitSeconds); + eh.setCheckSuccess(checkSuccess); + CHK(sequence.insert(eh), ctxc); + }; -void initScexSequence(Subsystem* ss, ModeListEntry& eh) {} + // Build Earth Observation target + iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_EARTH_OBSV_TGT.second); + iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_EARTH_OBSV_TGT.second); + iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_EARTH_OBSV_TGT.second); + iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::MPSOC_ON, PL_TABLE_EARTH_OBSV_TGT.second); + ss->addTable(TableEntry(PL_TABLE_EARTH_OBSV_TGT.first, &PL_TABLE_EARTH_OBSV_TGT.second)); + + // Build Earth Observation transition 0 + iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_EARTH_OBSV_TRANS_0.second); + iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_EARTH_OBSV_TRANS_0.second); + iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_EARTH_OBSV_TRANS_0.second); + ss->addTable(TableEntry(PL_TABLE_EARTH_OBSV_TRANS_0.first, &PL_TABLE_EARTH_OBSV_TRANS_0.second)); + + // Build Earth Observation transition 1 + iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::MPSOC_ON, PL_TABLE_EARTH_OBSV_TRANS_1.second); + ss->addTable(TableEntry(PL_TABLE_EARTH_OBSV_TRANS_1.first, &PL_TABLE_EARTH_OBSV_TRANS_1.second)); + + ihs(PL_SEQUENCE_EARTH_OBSV.second, PL_TABLE_EARTH_OBSV_TGT.first, 0, true); + ihs(PL_SEQUENCE_EARTH_OBSV.second, PL_TABLE_EARTH_OBSV_TRANS_0.first, 0, true); + ihs(PL_SEQUENCE_EARTH_OBSV.second, PL_TABLE_EARTH_OBSV_TRANS_1.first, 0, false); + ss->addSequence(SequenceEntry(PL_SEQUENCE_EARTH_OBSV.first, &PL_SEQUENCE_EARTH_OBSV.second, + PL_SEQUENCE_OFF.first)); +} + +void initScexSequence(Subsystem* ss, ModeListEntry& eh) { + std::string context = "satsystem::payload::initScexSequence"; + auto ctxc = context.c_str(); + // Insert Helper Table + auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, + ArrayList& sequence) { + eh.setObject(obj); + eh.setMode(mode); + eh.setSubmode(submode); + CHK(sequence.insert(eh), ctxc); + }; + // Insert Helper Sequence + auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, + bool checkSuccess) { + eh.setTableId(tableId); + eh.setWaitSeconds(waitSeconds); + eh.setCheckSuccess(checkSuccess); + CHK(sequence.insert(eh), ctxc); + }; + + // Build SCEX target + iht(objects::SCEX_HANDLER, NML, 0, PL_TABLE_SCEX_TGT.second); + ss->addTable(TableEntry(PL_TABLE_EARTH_OBSV_TGT.first, &PL_TABLE_EARTH_OBSV_TGT.second)); + + // Build SCEX transition 0 + iht(objects::SCEX_HANDLER, NML, 0, PL_TABLE_SCEX_TGT.second); + ss->addTable(TableEntry(PL_TABLE_SCEX_TRANS_0.first, &PL_TABLE_SCEX_TRANS_0.second)); + + // Build SCEX sequence + ihs(PL_SEQUENCE_SCEX.second, PL_TABLE_SCEX_TGT.first, 0, true); + ihs(PL_SEQUENCE_SCEX.second, PL_TABLE_SCEX_TRANS_0.first, 0, false); + ss->addSequence( + SequenceEntry(PL_SEQUENCE_SCEX.first, &PL_SEQUENCE_SCEX.second, PL_SEQUENCE_OFF.first)); +} void checkInsert(ReturnValue_t result, const char* ctx) { if (result != HasReturnvaluesIF::RETURN_OK) { From 9c0a89bbdcd2bddfee2f18b4ea7fa2a3ca6b87ff Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 28 Apr 2022 16:20:41 +0200 Subject: [PATCH 004/176] added all checks, made checker func generic --- mission/system/tree/CMakeLists.txt | 1 + mission/system/tree/acsModeTree.cpp | 126 +++++++++++------------- mission/system/tree/payloadModeTree.cpp | 118 ++++++++++++---------- mission/system/tree/util.cpp | 9 ++ mission/system/tree/util.h | 12 +++ 5 files changed, 149 insertions(+), 117 deletions(-) create mode 100644 mission/system/tree/util.cpp create mode 100644 mission/system/tree/util.h diff --git a/mission/system/tree/CMakeLists.txt b/mission/system/tree/CMakeLists.txt index c5bddc3f..908f4b3d 100644 --- a/mission/system/tree/CMakeLists.txt +++ b/mission/system/tree/CMakeLists.txt @@ -2,4 +2,5 @@ target_sources(${LIB_EIVE_MISSION} PRIVATE acsModeTree.cpp payloadModeTree.cpp system.cpp + util.cpp ) diff --git a/mission/system/tree/acsModeTree.cpp b/mission/system/tree/acsModeTree.cpp index 3fca1ce0..43ede7ae 100644 --- a/mission/system/tree/acsModeTree.cpp +++ b/mission/system/tree/acsModeTree.cpp @@ -7,10 +7,10 @@ #include #include "mission/controller/controllerdefinitions/AcsControllerDefinitions.h" +#include "util.h" // Alias for checker function namespace { -void checkInsert(ReturnValue_t result, const char* ctx); void buildOffSequence(Subsystem* ss, ModeListEntry& eh); void buildDetumbleSequence(Subsystem* ss, ModeListEntry& entryHelper); void buildSafeSequence(Subsystem* ss, ModeListEntry& entryHelper); @@ -19,7 +19,7 @@ void buildIdleChargeSequence(Subsystem* ss, ModeListEntry& entryHelper); void buildTargetPtSequence(Subsystem* ss, ModeListEntry& entryHelper); } // namespace -const auto CHK = checkInsert; +const auto check = subsystem::checkInsert; static const auto OFF = HasModesIF::MODE_OFF; static const auto NML = DeviceHandlerIF::MODE_NORMAL; @@ -97,7 +97,7 @@ void buildOffSequence(Subsystem* ss, ModeListEntry& eh) { eh.setObject(obj); eh.setMode(mode); eh.setSubmode(submode); - CHK(table.insert(eh), ctxc); + check(table.insert(eh), ctxc); }; // Insert Helper Sequence auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, @@ -105,11 +105,11 @@ void buildOffSequence(Subsystem* ss, ModeListEntry& eh) { eh.setTableId(tableId); eh.setWaitSeconds(waitSeconds); eh.setCheckSuccess(checkSuccess); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // OFF Target table is empty - CHK(ss->addTable(&ACS_TABLE_OFF_TGT.second, ACS_TABLE_OFF_TGT.first, false, true), ctxc); + check(ss->addTable(&ACS_TABLE_OFF_TGT.second, ACS_TABLE_OFF_TGT.first, false, true), ctxc); // Build OFF transition iht(objects::ACS_CONTROLLER, OFF, 0, ACS_TABLE_OFF_TRANS.second); @@ -118,14 +118,14 @@ void buildOffSequence(Subsystem* ss, ModeListEntry& eh) { iht(objects::ACS_BOARD_ASS, OFF, 0, ACS_TABLE_OFF_TRANS.second); iht(objects::SUS_BOARD_ASS, OFF, 0, ACS_TABLE_OFF_TRANS.second); iht(objects::RW_ASS, OFF, 0, ACS_TABLE_OFF_TRANS.second); - CHK(ss->addTable(&ACS_TABLE_OFF_TRANS.second, ACS_TABLE_OFF_TRANS.first, false, true), ctxc); + check(ss->addTable(&ACS_TABLE_OFF_TRANS.second, ACS_TABLE_OFF_TRANS.first, false, true), ctxc); // Build OFF sequence ihs(ACS_SEQUENCE_OFF.second, ACS_TABLE_OFF_TGT.first, 0, false); ihs(ACS_SEQUENCE_OFF.second, ACS_TABLE_OFF_TRANS.first, 0, false); - CHK(ss->addSequence(&ACS_SEQUENCE_OFF.second, ACS_SEQUENCE_OFF.first, ACS_SEQUENCE_OFF.first, - false, true), - ctxc); + check(ss->addSequence(&ACS_SEQUENCE_OFF.second, ACS_SEQUENCE_OFF.first, ACS_SEQUENCE_OFF.first, + false, true), + ctxc); } void buildSafeSequence(Subsystem* ss, ModeListEntry& eh) { @@ -137,7 +137,7 @@ void buildSafeSequence(Subsystem* ss, ModeListEntry& eh) { eh.setObject(obj); eh.setMode(mode); eh.setSubmode(submode); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Insert Helper Sequence auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, @@ -145,14 +145,14 @@ void buildSafeSequence(Subsystem* ss, ModeListEntry& eh) { eh.setTableId(tableId); eh.setWaitSeconds(waitSeconds); eh.setCheckSuccess(checkSuccess); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Build SAFE target iht(objects::ACS_CONTROLLER, acs::CtrlModes::SAFE, 0, ACS_TABLE_SAFE_TGT.second); iht(objects::IMTQ_HANDLER, NML, 0, ACS_TABLE_SAFE_TGT.second); iht(objects::SUS_BOARD_ASS, NML, 0, ACS_TABLE_SAFE_TGT.second); iht(objects::ACS_BOARD_ASS, NML, 0, ACS_TABLE_SAFE_TGT.second); - CHK(ss->addTable(&ACS_TABLE_SAFE_TGT.second, ACS_TABLE_OFF_TGT.first, false, true), ctxc); + check(ss->addTable(&ACS_TABLE_SAFE_TGT.second, ACS_TABLE_OFF_TGT.first, false, true), ctxc); // Build SAFE transition 0 iht(objects::IMTQ_HANDLER, NML, 0, ACS_TABLE_SAFE_TRANS_0.second); @@ -160,21 +160,21 @@ void buildSafeSequence(Subsystem* ss, ModeListEntry& eh) { iht(objects::ACS_BOARD_ASS, NML, 0, ACS_TABLE_SAFE_TRANS_0.second); iht(objects::STAR_TRACKER, OFF, 0, ACS_TABLE_SAFE_TRANS_0.second); iht(objects::RW_ASS, OFF, 0, ACS_TABLE_SAFE_TRANS_0.second); - CHK(ss->addTable(&ACS_TABLE_SAFE_TRANS_0.second, ACS_TABLE_SAFE_TRANS_0.first, false, true), - ctxc); + check(ss->addTable(&ACS_TABLE_SAFE_TRANS_0.second, ACS_TABLE_SAFE_TRANS_0.first, false, true), + ctxc); // Build SAFE transition 1 iht(objects::ACS_CONTROLLER, acs::CtrlModes::SAFE, 0, ACS_TABLE_SAFE_TRANS_1.second); - CHK(ss->addTable(&ACS_TABLE_SAFE_TRANS_1.second, ACS_TABLE_SAFE_TRANS_1.first, false, true), - ctxc); + check(ss->addTable(&ACS_TABLE_SAFE_TRANS_1.second, ACS_TABLE_SAFE_TRANS_1.first, false, true), + ctxc); // Build SAFE sequence ihs(ACS_SEQUENCE_SAFE.second, ACS_TABLE_SAFE_TGT.first, 0, true); ihs(ACS_SEQUENCE_SAFE.second, ACS_TABLE_SAFE_TRANS_0.first, 0, false); ihs(ACS_SEQUENCE_SAFE.second, ACS_TABLE_SAFE_TRANS_1.first, 0, false); - CHK(ss->addSequence(&ACS_SEQUENCE_SAFE.second, ACS_SEQUENCE_SAFE.first, ACS_SEQUENCE_OFF.first, - false, true), - ctxc); + check(ss->addSequence(&ACS_SEQUENCE_SAFE.second, ACS_SEQUENCE_SAFE.first, ACS_SEQUENCE_OFF.first, + false, true), + ctxc); } void buildDetumbleSequence(Subsystem* ss, ModeListEntry& eh) { @@ -186,7 +186,7 @@ void buildDetumbleSequence(Subsystem* ss, ModeListEntry& eh) { eh.setObject(obj); eh.setMode(mode); eh.setSubmode(submode); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Insert Helper Sequence auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, @@ -194,15 +194,15 @@ void buildDetumbleSequence(Subsystem* ss, ModeListEntry& eh) { eh.setTableId(tableId); eh.setWaitSeconds(waitSeconds); eh.setCheckSuccess(checkSuccess); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Build DETUMBLE target iht(objects::ACS_CONTROLLER, acs::CtrlModes::DETUMBLE, 0, ACS_TABLE_DETUMBLE_TGT.second); iht(objects::IMTQ_HANDLER, NML, 0, ACS_TABLE_DETUMBLE_TGT.second); iht(objects::SUS_BOARD_ASS, NML, 0, ACS_TABLE_DETUMBLE_TGT.second); iht(objects::ACS_BOARD_ASS, NML, 0, ACS_TABLE_DETUMBLE_TGT.second); - CHK(ss->addTable(&ACS_TABLE_DETUMBLE_TGT.second, ACS_TABLE_DETUMBLE_TGT.first, false, true), - ctxc); + check(ss->addTable(&ACS_TABLE_DETUMBLE_TGT.second, ACS_TABLE_DETUMBLE_TGT.first, false, true), + ctxc); // Build DETUMBLE transition 0 iht(objects::IMTQ_HANDLER, NML, 0, ACS_TABLE_DETUMBLE_TRANS_0.second); @@ -210,23 +210,23 @@ void buildDetumbleSequence(Subsystem* ss, ModeListEntry& eh) { iht(objects::SUS_BOARD_ASS, NML, 0, ACS_TABLE_DETUMBLE_TRANS_0.second); iht(objects::STAR_TRACKER, OFF, 0, ACS_TABLE_DETUMBLE_TRANS_0.second); iht(objects::RW_ASS, OFF, 0, ACS_TABLE_DETUMBLE_TRANS_0.second); - CHK(ss->addTable(&ACS_TABLE_DETUMBLE_TRANS_0.second, ACS_TABLE_DETUMBLE_TRANS_0.first, false, - true), - ctxc); + check(ss->addTable(&ACS_TABLE_DETUMBLE_TRANS_0.second, ACS_TABLE_DETUMBLE_TRANS_0.first, false, + true), + ctxc); // Build DETUMBLE transition 1 iht(objects::ACS_CONTROLLER, acs::CtrlModes::DETUMBLE, 0, ACS_TABLE_DETUMBLE_TRANS_1.second); - CHK(ss->addTable(&ACS_TABLE_DETUMBLE_TRANS_1.second, ACS_TABLE_DETUMBLE_TRANS_1.first, false, - true), - ctxc); + check(ss->addTable(&ACS_TABLE_DETUMBLE_TRANS_1.second, ACS_TABLE_DETUMBLE_TRANS_1.first, false, + true), + ctxc); // Build DETUMBLE sequence ihs(ACS_SEQUENCE_DETUMBLE.second, ACS_TABLE_DETUMBLE_TGT.first, 0, true); ihs(ACS_SEQUENCE_DETUMBLE.second, ACS_TABLE_DETUMBLE_TRANS_0.first, 0, false); ihs(ACS_SEQUENCE_DETUMBLE.second, ACS_TABLE_DETUMBLE_TRANS_1.first, 0, false); - CHK(ss->addSequence(&ACS_SEQUENCE_DETUMBLE.second, ACS_SEQUENCE_DETUMBLE.first, - ACS_SEQUENCE_SAFE.first, false, true), - ctxc); + check(ss->addSequence(&ACS_SEQUENCE_DETUMBLE.second, ACS_SEQUENCE_DETUMBLE.first, + ACS_SEQUENCE_SAFE.first, false, true), + ctxc); } void buildIdleSequence(Subsystem* ss, ModeListEntry& eh) { @@ -238,7 +238,7 @@ void buildIdleSequence(Subsystem* ss, ModeListEntry& eh) { eh.setObject(obj); eh.setMode(mode); eh.setSubmode(submode); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Insert Helper Sequence auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, @@ -246,7 +246,7 @@ void buildIdleSequence(Subsystem* ss, ModeListEntry& eh) { eh.setTableId(tableId); eh.setWaitSeconds(waitSeconds); eh.setCheckSuccess(checkSuccess); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Build IDLE target iht(objects::ACS_CONTROLLER, acs::CtrlModes::IDLE, 0, ACS_TABLE_IDLE_TGT.second); @@ -285,7 +285,7 @@ void buildIdleChargeSequence(Subsystem* ss, ModeListEntry& eh) { eh.setObject(obj); eh.setMode(mode); eh.setSubmode(submode); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Insert Helper Sequence auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, @@ -293,7 +293,7 @@ void buildIdleChargeSequence(Subsystem* ss, ModeListEntry& eh) { eh.setTableId(tableId); eh.setWaitSeconds(waitSeconds); eh.setCheckSuccess(checkSuccess); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Build IDLE target iht(objects::ACS_CONTROLLER, acs::CtrlModes::IDLE, acs::IDLE_CHARGE, @@ -301,8 +301,8 @@ void buildIdleChargeSequence(Subsystem* ss, ModeListEntry& eh) { iht(objects::IMTQ_HANDLER, NML, 0, ACS_TABLE_IDLE_CHRG_TGT.second); iht(objects::SUS_BOARD_ASS, NML, 0, ACS_TABLE_IDLE_CHRG_TGT.second); iht(objects::ACS_BOARD_ASS, NML, 0, ACS_TABLE_IDLE_CHRG_TGT.second); - CHK(ss->addTable(&ACS_TABLE_IDLE_CHRG_TGT.second, ACS_TABLE_IDLE_CHRG_TGT.first, false, true), - ctxc); + check(ss->addTable(&ACS_TABLE_IDLE_CHRG_TGT.second, ACS_TABLE_IDLE_CHRG_TGT.first, false, true), + ctxc); // Build IDLE transition 0 iht(objects::IMTQ_HANDLER, NML, 0, ACS_TABLE_IDLE_CHRG_TRANS_0.second); @@ -310,24 +310,24 @@ void buildIdleChargeSequence(Subsystem* ss, ModeListEntry& eh) { iht(objects::SUS_BOARD_ASS, NML, 0, ACS_TABLE_IDLE_CHRG_TRANS_0.second); iht(objects::RW_ASS, OFF, 0, ACS_TABLE_IDLE_CHRG_TRANS_0.second); iht(objects::STAR_TRACKER, OFF, 0, ACS_TABLE_IDLE_CHRG_TRANS_0.second); - CHK(ss->addTable(&ACS_TABLE_IDLE_CHRG_TRANS_0.second, ACS_TABLE_IDLE_CHRG_TRANS_0.first, false, - true), - ctxc); + check(ss->addTable(&ACS_TABLE_IDLE_CHRG_TRANS_0.second, ACS_TABLE_IDLE_CHRG_TRANS_0.first, false, + true), + ctxc); // Build IDLE transition 1 iht(objects::ACS_CONTROLLER, acs::CtrlModes::IDLE, acs::IDLE_CHARGE, ACS_TABLE_IDLE_CHRG_TRANS_1.second); - CHK(ss->addTable(&ACS_TABLE_IDLE_CHRG_TRANS_1.second, ACS_TABLE_IDLE_CHRG_TRANS_1.first, false, - true), - ctxc); + check(ss->addTable(&ACS_TABLE_IDLE_CHRG_TRANS_1.second, ACS_TABLE_IDLE_CHRG_TRANS_1.first, false, + true), + ctxc); // Build IDLE sequence ihs(ACS_SEQUENCE_IDLE_CHRG.second, ACS_TABLE_IDLE_CHRG_TGT.first, 0, true); ihs(ACS_SEQUENCE_IDLE_CHRG.second, ACS_TABLE_IDLE_CHRG_TRANS_0.first, 0, true); ihs(ACS_SEQUENCE_IDLE_CHRG.second, ACS_TABLE_IDLE_CHRG_TRANS_1.first, 0, false); - CHK(ss->addSequence(&ACS_SEQUENCE_IDLE_CHRG.second, ACS_SEQUENCE_IDLE_CHRG.first, - ACS_SEQUENCE_SAFE.first, false, true), - ctxc); + check(ss->addSequence(&ACS_SEQUENCE_IDLE_CHRG.second, ACS_SEQUENCE_IDLE_CHRG.first, + ACS_SEQUENCE_SAFE.first, false, true), + ctxc); } void buildTargetPtSequence(Subsystem* ss, ModeListEntry& eh) { @@ -339,7 +339,7 @@ void buildTargetPtSequence(Subsystem* ss, ModeListEntry& eh) { eh.setObject(obj); eh.setMode(mode); eh.setSubmode(submode); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Insert Helper Sequence auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, @@ -347,7 +347,7 @@ void buildTargetPtSequence(Subsystem* ss, ModeListEntry& eh) { eh.setTableId(tableId); eh.setWaitSeconds(waitSeconds); eh.setCheckSuccess(checkSuccess); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Build TARGET PT table @@ -357,8 +357,8 @@ void buildTargetPtSequence(Subsystem* ss, ModeListEntry& eh) { iht(objects::ACS_BOARD_ASS, NML, 0, ACS_TABLE_TARGET_PT_TGT.second); iht(objects::RW_ASS, NML, 0, ACS_TABLE_TARGET_PT_TGT.second); iht(objects::STAR_TRACKER, NML, 0, ACS_TABLE_TARGET_PT_TGT.second); - CHK(ss->addTable(&ACS_TABLE_TARGET_PT_TGT.second, ACS_TABLE_TARGET_PT_TGT.first, false, true), - ctxc); + check(ss->addTable(&ACS_TABLE_TARGET_PT_TGT.second, ACS_TABLE_TARGET_PT_TGT.first, false, true), + ctxc); // Build TARGET PT transition 0 iht(objects::IMTQ_HANDLER, NML, 0, ACS_TABLE_TARGET_PT_TRANS_0.second); @@ -366,29 +366,23 @@ void buildTargetPtSequence(Subsystem* ss, ModeListEntry& eh) { iht(objects::ACS_BOARD_ASS, NML, 0, ACS_TABLE_TARGET_PT_TRANS_0.second); iht(objects::RW_ASS, NML, 0, ACS_TABLE_TARGET_PT_TRANS_0.second); iht(objects::STAR_TRACKER, NML, 0, ACS_TABLE_TARGET_PT_TRANS_0.second); - CHK(ss->addTable(&ACS_TABLE_TARGET_PT_TRANS_0.second, ACS_TABLE_TARGET_PT_TRANS_0.first, false, - true), - ctxc); + check(ss->addTable(&ACS_TABLE_TARGET_PT_TRANS_0.second, ACS_TABLE_TARGET_PT_TRANS_0.first, false, + true), + ctxc); // Build TARGET PT transition 1 iht(objects::ACS_CONTROLLER, acs::CtrlModes::TARGET_PT, 0, ACS_TABLE_TARGET_PT_TRANS_1.second); - CHK(ss->addTable(&ACS_TABLE_TARGET_PT_TRANS_1.second, ACS_TABLE_TARGET_PT_TRANS_1.first, false, - true), - ctxc); + check(ss->addTable(&ACS_TABLE_TARGET_PT_TRANS_1.second, ACS_TABLE_TARGET_PT_TRANS_1.first, false, + true), + ctxc); // Build IDLE sequence ihs(ACS_SEQUENCE_TARGET_PT.second, ACS_TABLE_TARGET_PT_TGT.first, 0, true); ihs(ACS_SEQUENCE_TARGET_PT.second, ACS_TABLE_TARGET_PT_TRANS_0.first, 0, true); ihs(ACS_SEQUENCE_TARGET_PT.second, ACS_TABLE_TARGET_PT_TRANS_1.first, 0, false); - CHK(ss->addSequence(&ACS_SEQUENCE_TARGET_PT.second, ACS_SEQUENCE_TARGET_PT.first, - ACS_SEQUENCE_IDLE.first, false, true), - ctxc); -} - -void checkInsert(ReturnValue_t result, const char* ctx) { - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "Insertion failed at " << ctx << std::endl; - } + check(ss->addSequence(&ACS_SEQUENCE_TARGET_PT.second, ACS_SEQUENCE_TARGET_PT.first, + ACS_SEQUENCE_IDLE.first, false, true), + ctxc); } } // namespace diff --git a/mission/system/tree/payloadModeTree.cpp b/mission/system/tree/payloadModeTree.cpp index ad65230f..d5779120 100644 --- a/mission/system/tree/payloadModeTree.cpp +++ b/mission/system/tree/payloadModeTree.cpp @@ -9,9 +9,9 @@ #include "mission/devices/devicedefinitions/payloadPcduDefinitions.h" #include "mission/system/objects/PayloadSubsystem.h" #include "mission/system/objects/definitions.h" +#include "util.h" namespace { -void checkInsert(ReturnValue_t result, const char* ctx); void initOffSequence(Subsystem* ss, ModeListEntry& eh); void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh); void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh); @@ -20,7 +20,7 @@ void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh); void initScexSequence(Subsystem* ss, ModeListEntry& eh); } // namespace -const auto CHK = checkInsert; +const auto check = subsystem::checkInsert; static const auto OFF = HasModesIF::MODE_OFF; static const auto ON = HasModesIF::MODE_ON; static const auto NML = DeviceHandlerIF::MODE_NORMAL; @@ -95,7 +95,7 @@ void initOffSequence(Subsystem* ss, ModeListEntry& eh) { eh.setObject(obj); eh.setMode(mode); eh.setSubmode(submode); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Insert Helper Sequence auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, @@ -103,11 +103,11 @@ void initOffSequence(Subsystem* ss, ModeListEntry& eh) { eh.setTableId(tableId); eh.setWaitSeconds(waitSeconds); eh.setCheckSuccess(checkSuccess); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Build OFF target. Is empty - ss->addTable(&PL_TABLE_OFF_TGT.second, PL_TABLE_OFF_TGT.first, false, true); + check(ss->addTable(TableEntry(PL_TABLE_OFF_TGT.first, &PL_TABLE_OFF_TGT.second)), ctxc); // Build OFF transition 0 iht(objects::PLOC_SWITCHER, OFF, 0, PL_TABLE_OFF_TRANS.second); @@ -115,13 +115,14 @@ void initOffSequence(Subsystem* ss, ModeListEntry& eh) { iht(objects::SCEX_HANDLER, OFF, 0, PL_TABLE_OFF_TRANS.second); iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_OFF_TRANS.second); iht(objects::PLOC_SUBSYSTEM, OFF, 0, PL_TABLE_OFF_TRANS.second); - ss->addTable(&PL_TABLE_OFF_TRANS.second, PL_TABLE_OFF_TRANS.first, false, true); + check(ss->addTable(TableEntry(PL_TABLE_OFF_TRANS.first, &PL_TABLE_OFF_TRANS.second)), ctxc); // Build OFF sequence ihs(PL_SEQUENCE_OFF.second, PL_TABLE_OFF_TGT.first, 0, false); ihs(PL_SEQUENCE_OFF.second, PL_TABLE_OFF_TRANS.first, 0, false); - ss->addSequence(&PL_SEQUENCE_OFF.second, PL_SEQUENCE_OFF.first, PL_SEQUENCE_OFF.first, false, - true); + check(ss->addSequence( + SequenceEntry(PL_SEQUENCE_OFF.first, &PL_SEQUENCE_OFF.second, PL_SEQUENCE_OFF.first)), + ctxc); } void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh) { @@ -133,7 +134,7 @@ void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh) { eh.setObject(obj); eh.setMode(mode); eh.setSubmode(submode); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Insert Helper Sequence auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, @@ -141,7 +142,7 @@ void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh) { eh.setTableId(tableId); eh.setWaitSeconds(waitSeconds); eh.setCheckSuccess(checkSuccess); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Build MPSoC stream target @@ -150,26 +151,31 @@ void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh) { iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_MPSOC_STREAM_TGT.second); iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_MPSOC_STREAM_TGT.second); iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::MPSOC_ON, PL_TABLE_MPSOC_STREAM_TGT.second); - ss->addTable(&PL_TABLE_MPSOC_STREAM_TGT.second, PL_TABLE_MPSOC_STREAM_TGT.first, false, true); + check( + ss->addTable(TableEntry(PL_TABLE_MPSOC_STREAM_TGT.first, &PL_TABLE_MPSOC_STREAM_TGT.second)), + ctxc); // Build MPSoC stream transition 0 iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); iht(objects::SCEX_HANDLER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); - ss->addTable(&PL_TABLE_MPSOC_STREAM_TRANS_0.second, PL_TABLE_MPSOC_STREAM_TRANS_0.first, false, - true); + check(ss->addTable( + TableEntry(PL_TABLE_MPSOC_STREAM_TRANS_0.first, &PL_TABLE_MPSOC_STREAM_TRANS_0.second)), + ctxc); // Build MPSoC stream transition 1 iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::MPSOC_ON, PL_TABLE_MPSOC_STREAM_TRANS_1.second); - ss->addTable(&PL_TABLE_MPSOC_STREAM_TRANS_1.second, PL_TABLE_MPSOC_STREAM_TRANS_1.first, false, - true); + check(ss->addTable( + TableEntry(PL_TABLE_MPSOC_STREAM_TRANS_1.first, &PL_TABLE_MPSOC_STREAM_TRANS_1.second)), + ctxc); // Build MPSoC stream sequence ihs(PL_SEQUENCE_MPSOC_STREAM.second, PL_TABLE_MPSOC_STREAM_TGT.first, 0, true); ihs(PL_SEQUENCE_MPSOC_STREAM.second, PL_TABLE_MPSOC_STREAM_TRANS_0.first, 0, true); ihs(PL_SEQUENCE_MPSOC_STREAM.second, PL_TABLE_MPSOC_STREAM_TRANS_1.first, 0, false); - ss->addSequence(&PL_SEQUENCE_MPSOC_STREAM.second, PL_SEQUENCE_MPSOC_STREAM.first, - PL_SEQUENCE_OFF.first, false, true); + check(ss->addSequence(SequenceEntry(PL_SEQUENCE_MPSOC_STREAM.first, + &PL_SEQUENCE_MPSOC_STREAM.second, PL_SEQUENCE_OFF.first)), + ctxc); } void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh) { @@ -181,7 +187,7 @@ void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh) { eh.setObject(obj); eh.setMode(mode); eh.setSubmode(submode); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Insert Helper Sequence auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, @@ -189,34 +195,38 @@ void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh) { eh.setTableId(tableId); eh.setWaitSeconds(waitSeconds); eh.setCheckSuccess(checkSuccess); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Build CAM target // Only check that the PL PCDU is on for now. It might later become necessary to switch on // the PLOC, so we ignore its state. iht(objects::PLPCDU_HANDLER, NML, plpcdu::ALL_ON_SUBMODE, PL_TABLE_CAM_STREAM_TGT.second); - ss->addTable(&PL_TABLE_CAM_STREAM_TGT.second, PL_TABLE_CAM_STREAM_TGT.first, false, true); + check(ss->addTable(TableEntry(PL_TABLE_CAM_STREAM_TGT.first, &PL_TABLE_CAM_STREAM_TGT.second)), + ctxc); // Build CAM transition 0 // PLOC is actively commanded off here iht(objects::PLOC_SUBSYSTEM, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); iht(objects::SCEX_HANDLER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); - ss->addTable(&PL_TABLE_MPSOC_STREAM_TRANS_0.second, PL_TABLE_MPSOC_STREAM_TRANS_0.first, false, - true); + check(ss->addTable( + TableEntry(PL_TABLE_MPSOC_STREAM_TRANS_0.first, &PL_TABLE_MPSOC_STREAM_TRANS_0.second)), + ctxc); // Build CAM transition 1 iht(objects::PLOC_SWITCHER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_1.second); - ss->addTable(&PL_TABLE_MPSOC_STREAM_TRANS_1.second, PL_TABLE_MPSOC_STREAM_TRANS_1.first, false, - true); + check(ss->addTable( + TableEntry(PL_TABLE_MPSOC_STREAM_TRANS_1.first, &PL_TABLE_MPSOC_STREAM_TRANS_1.second)), + ctxc); // Build CAM stream sequence ihs(PL_SEQUENCE_CAM_STREAM.second, PL_TABLE_CAM_STREAM_TGT.first, 0, true); ihs(PL_SEQUENCE_CAM_STREAM.second, PL_TABLE_CAM_STREAM_TRANS_0.first, 0, true); ihs(PL_SEQUENCE_CAM_STREAM.second, PL_TABLE_CAM_STREAM_TRANS_1.first, 0, false); - ss->addSequence(&PL_SEQUENCE_CAM_STREAM.second, PL_SEQUENCE_CAM_STREAM.first, - PL_SEQUENCE_OFF.first, false, true); + check(ss->addSequence(SequenceEntry(PL_SEQUENCE_CAM_STREAM.first, &PL_SEQUENCE_CAM_STREAM.second, + PL_SEQUENCE_OFF.first)), + ctxc); } void initPlSpvSequence(Subsystem* ss, ModeListEntry& eh) { @@ -228,7 +238,7 @@ void initPlSpvSequence(Subsystem* ss, ModeListEntry& eh) { eh.setObject(obj); eh.setMode(mode); eh.setSubmode(submode); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Insert Helper Sequence auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, @@ -236,18 +246,21 @@ void initPlSpvSequence(Subsystem* ss, ModeListEntry& eh) { eh.setTableId(tableId); eh.setWaitSeconds(waitSeconds); eh.setCheckSuccess(checkSuccess); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Build Payload Supervisor Only target iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_SUPV_ONLY_TGT.second); iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::SUPV_ONLY, PL_TABLE_SUPV_ONLY_TGT.second); - ss->addTable(TableEntry(PL_TABLE_SUPV_ONLY_TGT.first, &PL_TABLE_SUPV_ONLY_TGT.second)); + check(ss->addTable(TableEntry(PL_TABLE_SUPV_ONLY_TGT.first, &PL_TABLE_SUPV_ONLY_TGT.second)), + ctxc); // Build Payload Supervisor Only transition 0 iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_SUPV_ONLY_TRANS_0.second); iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_SUPV_ONLY_TRANS_0.second); - ss->addTable(TableEntry(PL_TABLE_SUPV_ONLY_TRANS_0.first, &PL_TABLE_SUPV_ONLY_TRANS_0.second)); + check(ss->addTable( + TableEntry(PL_TABLE_SUPV_ONLY_TRANS_0.first, &PL_TABLE_SUPV_ONLY_TRANS_0.second)), + ctxc); // Build Payload Supervisor Only transition 1 iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::SUPV_ONLY, PL_TABLE_SUPV_ONLY_TRANS_1.second); @@ -256,8 +269,9 @@ void initPlSpvSequence(Subsystem* ss, ModeListEntry& eh) { ihs(PL_SEQUENCE_SUPV_ONLY.second, PL_TABLE_SUPV_ONLY_TGT.first, 0, true); ihs(PL_SEQUENCE_SUPV_ONLY.second, PL_TABLE_SUPV_ONLY_TRANS_0.first, 0, true); ihs(PL_SEQUENCE_SUPV_ONLY.second, PL_TABLE_SUPV_ONLY_TRANS_1.first, 0, false); - ss->addSequence(SequenceEntry(PL_SEQUENCE_SUPV_ONLY.first, &PL_SEQUENCE_SUPV_ONLY.second, - PL_SEQUENCE_OFF.first)); + check(ss->addSequence(SequenceEntry(PL_SEQUENCE_SUPV_ONLY.first, &PL_SEQUENCE_SUPV_ONLY.second, + PL_SEQUENCE_OFF.first)), + ctxc); } void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh) { @@ -269,7 +283,7 @@ void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh) { eh.setObject(obj); eh.setMode(mode); eh.setSubmode(submode); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Insert Helper Sequence auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, @@ -277,7 +291,7 @@ void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh) { eh.setTableId(tableId); eh.setWaitSeconds(waitSeconds); eh.setCheckSuccess(checkSuccess); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Build Earth Observation target @@ -285,23 +299,29 @@ void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh) { iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_EARTH_OBSV_TGT.second); iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_EARTH_OBSV_TGT.second); iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::MPSOC_ON, PL_TABLE_EARTH_OBSV_TGT.second); - ss->addTable(TableEntry(PL_TABLE_EARTH_OBSV_TGT.first, &PL_TABLE_EARTH_OBSV_TGT.second)); + check(ss->addTable(TableEntry(PL_TABLE_EARTH_OBSV_TGT.first, &PL_TABLE_EARTH_OBSV_TGT.second)), + ctxc); // Build Earth Observation transition 0 iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_EARTH_OBSV_TRANS_0.second); iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_EARTH_OBSV_TRANS_0.second); iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_EARTH_OBSV_TRANS_0.second); - ss->addTable(TableEntry(PL_TABLE_EARTH_OBSV_TRANS_0.first, &PL_TABLE_EARTH_OBSV_TRANS_0.second)); + check(ss->addTable( + TableEntry(PL_TABLE_EARTH_OBSV_TRANS_0.first, &PL_TABLE_EARTH_OBSV_TRANS_0.second)), + ctxc); // Build Earth Observation transition 1 iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::MPSOC_ON, PL_TABLE_EARTH_OBSV_TRANS_1.second); - ss->addTable(TableEntry(PL_TABLE_EARTH_OBSV_TRANS_1.first, &PL_TABLE_EARTH_OBSV_TRANS_1.second)); + check(ss->addTable( + TableEntry(PL_TABLE_EARTH_OBSV_TRANS_1.first, &PL_TABLE_EARTH_OBSV_TRANS_1.second)), + ctxc); ihs(PL_SEQUENCE_EARTH_OBSV.second, PL_TABLE_EARTH_OBSV_TGT.first, 0, true); ihs(PL_SEQUENCE_EARTH_OBSV.second, PL_TABLE_EARTH_OBSV_TRANS_0.first, 0, true); ihs(PL_SEQUENCE_EARTH_OBSV.second, PL_TABLE_EARTH_OBSV_TRANS_1.first, 0, false); - ss->addSequence(SequenceEntry(PL_SEQUENCE_EARTH_OBSV.first, &PL_SEQUENCE_EARTH_OBSV.second, - PL_SEQUENCE_OFF.first)); + check(ss->addSequence(SequenceEntry(PL_SEQUENCE_EARTH_OBSV.first, &PL_SEQUENCE_EARTH_OBSV.second, + PL_SEQUENCE_OFF.first)), + ctxc); } void initScexSequence(Subsystem* ss, ModeListEntry& eh) { @@ -313,7 +333,7 @@ void initScexSequence(Subsystem* ss, ModeListEntry& eh) { eh.setObject(obj); eh.setMode(mode); eh.setSubmode(submode); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Insert Helper Sequence auto ihs = [&](ArrayList& sequence, Mode_t tableId, uint32_t waitSeconds, @@ -321,28 +341,24 @@ void initScexSequence(Subsystem* ss, ModeListEntry& eh) { eh.setTableId(tableId); eh.setWaitSeconds(waitSeconds); eh.setCheckSuccess(checkSuccess); - CHK(sequence.insert(eh), ctxc); + check(sequence.insert(eh), ctxc); }; // Build SCEX target iht(objects::SCEX_HANDLER, NML, 0, PL_TABLE_SCEX_TGT.second); - ss->addTable(TableEntry(PL_TABLE_EARTH_OBSV_TGT.first, &PL_TABLE_EARTH_OBSV_TGT.second)); + check(ss->addTable(TableEntry(PL_TABLE_EARTH_OBSV_TGT.first, &PL_TABLE_EARTH_OBSV_TGT.second)), + ctxc); // Build SCEX transition 0 iht(objects::SCEX_HANDLER, NML, 0, PL_TABLE_SCEX_TGT.second); - ss->addTable(TableEntry(PL_TABLE_SCEX_TRANS_0.first, &PL_TABLE_SCEX_TRANS_0.second)); + check(ss->addTable(TableEntry(PL_TABLE_SCEX_TRANS_0.first, &PL_TABLE_SCEX_TRANS_0.second)), ctxc); // Build SCEX sequence ihs(PL_SEQUENCE_SCEX.second, PL_TABLE_SCEX_TGT.first, 0, true); ihs(PL_SEQUENCE_SCEX.second, PL_TABLE_SCEX_TRANS_0.first, 0, false); - ss->addSequence( - SequenceEntry(PL_SEQUENCE_SCEX.first, &PL_SEQUENCE_SCEX.second, PL_SEQUENCE_OFF.first)); -} - -void checkInsert(ReturnValue_t result, const char* ctx) { - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "satsystem::checkInsert: PL | Insertion failed at " << ctx << std::endl; - } + check(ss->addSequence( + SequenceEntry(PL_SEQUENCE_SCEX.first, &PL_SEQUENCE_SCEX.second, PL_SEQUENCE_OFF.first)), + ctxc); } } // namespace diff --git a/mission/system/tree/util.cpp b/mission/system/tree/util.cpp new file mode 100644 index 00000000..2a93efd8 --- /dev/null +++ b/mission/system/tree/util.cpp @@ -0,0 +1,9 @@ +#include "util.h" + +#include "fsfw/serviceinterface.h" + +void subsystem::checkInsert(ReturnValue_t result, const char* ctx) { + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "satsystem::checkInsert: Insertion failed at " << ctx << std::endl; + } +} diff --git a/mission/system/tree/util.h b/mission/system/tree/util.h new file mode 100644 index 00000000..5caf8e6d --- /dev/null +++ b/mission/system/tree/util.h @@ -0,0 +1,12 @@ +#ifndef MISSION_SYSTEM_TREE_UTIL_H_ +#define MISSION_SYSTEM_TREE_UTIL_H_ + +#include + +namespace subsystem { + +void checkInsert(ReturnValue_t result, const char* ctx); + +} + +#endif /* MISSION_SYSTEM_TREE_UTIL_H_ */ From b49ed2bacf0501998cfa40069ad45a8ff16f7178 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 3 May 2022 16:03:57 +0200 Subject: [PATCH 005/176] fsfw update --- fsfw | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fsfw b/fsfw index 7760b306..7f6c8b8b 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 7760b3063ee9249316edd1772384474676b062b2 +Subproject commit 7f6c8b8b123a63546de0d73f0de35900d6c806bf From c86e000f09a6bc0e4a947b02d37c42a408863046 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 25 May 2022 10:25:40 +0200 Subject: [PATCH 006/176] Update PL SS --- bsp_q7s/core/ObjectFactory.cpp | 110 ++++----------------------------- bsp_q7s/fmObjectFactory.cpp | 4 +- common/config/commonObjects.h | 1 + 3 files changed, 14 insertions(+), 101 deletions(-) diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index 1bf763d2..81a28291 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -36,15 +36,12 @@ #include "linux/obc/PdecHandler.h" #include "linux/obc/Ptme.h" #include "linux/obc/PtmeConfig.h" +#include "mission/system/objects/RwAssembly.h" #include "mission/system/fdir/AcsBoardFdir.h" #include "mission/system/fdir/GomspacePowerFdir.h" #include "mission/system/fdir/RtdFdir.h" #include "mission/system/fdir/SusFdir.h" #include "mission/system/fdir/SyrlinksFdir.h" -#include "mission/system/objects/RwAssembly.h" -#include "mission/system/objects/SusAssembly.h" -#include "mission/system/objects/TcsBoardAssembly.h" -#include "mission/system/tree/system.h" #include "tmtc/apid.h" #include "tmtc/pusIds.h" #if OBSW_TEST_LIBGPIOD == 1 @@ -96,10 +93,8 @@ #include "mission/tmtc/VirtualChannel.h" #include "mission/utility/TmFunnel.h" -ResetArgs RESET_ARGS_GNSS_0; -ResetArgs RESET_ARGS_GNSS_1; - -void ObjectFactory::setStatics() { Factory::setStaticFrameworkObjectIds(); } +ResetArgs resetArgsGnss0; +ResetArgs resetArgsGnss1; void Factory::setStaticFrameworkObjectIds() { PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; @@ -124,90 +119,7 @@ void Factory::setStaticFrameworkObjectIds() { TmPacketBase::timeStamperId = objects::TIME_STAMPER; } -void ObjectFactory::produce(void* args) { - ObjectFactory::setStatics(); - ObjectFactory::produceGenericObjects(); - - LinuxLibgpioIF* gpioComIF = nullptr; - UartComIF* uartComIF = nullptr; - SpiComIF* spiComIF = nullptr; - I2cComIF* i2cComIF = nullptr; - PowerSwitchIF* pwrSwitcher = nullptr; - - createCommunicationInterfaces(&gpioComIF, &uartComIF, &spiComIF, &i2cComIF); - createTmpComponents(); - new CoreController(objects::CORE_CONTROLLER); - - gpioCallbacks::disableAllDecoder(gpioComIF); - createPcduComponents(gpioComIF, &pwrSwitcher); - createRadSensorComponent(gpioComIF); - createSunSensorComponents(gpioComIF, spiComIF, pwrSwitcher, q7s::SPI_DEFAULT_DEV); - -#if OBSW_ADD_ACS_BOARD == 1 - createAcsBoardComponents(gpioComIF, uartComIF, pwrSwitcher); -#endif - createHeaterComponents(); - createSolarArrayDeploymentComponents(); - createPlPcduComponents(gpioComIF, spiComIF, pwrSwitcher); -#if OBSW_ADD_SYRLINKS == 1 - createSyrlinksComponents(pwrSwitcher); -#endif /* OBSW_ADD_SYRLINKS == 1 */ - createRtdComponents(q7s::SPI_DEFAULT_DEV, gpioComIF, pwrSwitcher); - createPayloadComponents(gpioComIF); - -#if OBSW_ADD_MGT == 1 - I2cCookie* imtqI2cCookie = - new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE, q7s::I2C_DEFAULT_DEV); - auto imtqHandler = new IMTQHandler(objects::IMTQ_HANDLER, objects::I2C_COM_IF, imtqI2cCookie, - pcdu::Switches::PDU1_CH3_MGT_5V); - imtqHandler->setPowerSwitcher(pwrSwitcher); - static_cast(imtqHandler); -#if OBSW_TEST_IMTQ == 1 - imtqHandler->setStartUpImmediately(); - imtqHandler->setToGoToNormal(true); -#endif -#if OBSW_DEBUG_IMTQ == 1 - imtqHandler->setDebugMode(true); -#endif -#endif - createReactionWheelComponents(gpioComIF); - -#if OBSW_ADD_BPX_BATTERY_HANDLER == 1 - I2cCookie* bpxI2cCookie = new I2cCookie(addresses::BPX_BATTERY, 100, q7s::I2C_DEFAULT_DEV); - BpxBatteryHandler* bpxHandler = - new BpxBatteryHandler(objects::BPX_BATT_HANDLER, objects::I2C_COM_IF, bpxI2cCookie); - bpxHandler->setStartUpImmediately(); - bpxHandler->setToGoToNormalMode(true); -#if OBSW_DEBUG_BPX_BATT == 1 - bpxHandler->setDebugMode(true); -#endif -#endif - new FileSystemHandler(objects::FILE_SYSTEM_HANDLER); - -#if OBSW_ADD_STAR_TRACKER == 1 - UartCookie* starTrackerCookie = - new UartCookie(objects::STAR_TRACKER, q7s::UART_STAR_TRACKER_DEV, uart::STAR_TRACKER_BAUD, - startracker::MAX_FRAME_SIZE * 2 + 2, UartModes::NON_CANONICAL); - starTrackerCookie->setNoFixedSizeReply(); - StrHelper* strHelper = new StrHelper(objects::STR_HELPER); - auto starTracker = - new StarTrackerHandler(objects::STAR_TRACKER, objects::UART_COM_IF, starTrackerCookie, - strHelper, pcdu::PDU1_CH2_STAR_TRACKER_5V); - starTracker->setPowerSwitcher(pwrSwitcher); - -#endif /* OBSW_ADD_STAR_TRACKER == 1 */ -#if OBSW_USE_CCSDS_IP_CORE == 1 - createCcsdsComponents(gpioComIF); -#endif /* OBSW_USE_CCSDS_IP_CORE == 1 */ - /* Test Task */ -#if OBSW_ADD_TEST_CODE == 1 - createTestComponents(gpioComIF); -#endif /* OBSW_ADD_TEST_CODE == 1 */ - new PlocUpdater(objects::PLOC_UPDATER); - new PlocMemoryDumper(objects::PLOC_MEMORY_DUMPER); - - satsystem::init(); -} +void ObjectFactory::setStatics() { Factory::setStaticFrameworkObjectIds(); } void ObjectFactory::createTmpComponents() { I2cCookie* i2cCookieTmp1075tcs1 = @@ -550,15 +462,15 @@ void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComI #if OBSW_DEBUG_GPS == 1 debugGps = true; #endif - RESET_ARGS_GNSS_1.gnss1 = true; - RESET_ARGS_GNSS_1.gpioComIF = gpioComIF; - RESET_ARGS_GNSS_1.waitPeriodMs = 100; - RESET_ARGS_GNSS_0.gnss1 = false; - RESET_ARGS_GNSS_0.gpioComIF = gpioComIF; - RESET_ARGS_GNSS_0.waitPeriodMs = 100; + resetArgsGnss1.gnss1 = true; + resetArgsGnss1.gpioComIF = gpioComIF; + resetArgsGnss1.waitPeriodMs = 100; + resetArgsGnss0.gnss1 = false; + resetArgsGnss0.gpioComIF = gpioComIF; + resetArgsGnss0.waitPeriodMs = 100; auto gpsHandler0 = new GPSHyperionLinuxController(objects::GPS_CONTROLLER, objects::NO_OBJECT, debugGps); - gpsHandler0->setResetPinTriggerFunction(gps::triggerGpioResetPin, &RESET_ARGS_GNSS_0); + gpsHandler0->setResetPinTriggerFunction(gps::triggerGpioResetPin, &resetArgsGnss0); AcsBoardHelper acsBoardHelper = AcsBoardHelper( objects::MGM_0_LIS3_HANDLER, objects::MGM_1_RM3100_HANDLER, objects::MGM_2_LIS3_HANDLER, diff --git a/bsp_q7s/fmObjectFactory.cpp b/bsp_q7s/fmObjectFactory.cpp index d81d6fe9..747d3871 100644 --- a/bsp_q7s/fmObjectFactory.cpp +++ b/bsp_q7s/fmObjectFactory.cpp @@ -8,7 +8,7 @@ #include "linux/ObjectFactory.h" #include "linux/callbacks/gpioCallbacks.h" #include "mission/core/GenericFactory.h" -#include "mission/system/tree/acsModeTree.h" +#include "mission/system/tree/system.h" void ObjectFactory::produce(void* args) { ObjectFactory::setStatics(); @@ -63,5 +63,5 @@ void ObjectFactory::produce(void* args) { #endif /* OBSW_ADD_TEST_CODE == 1 */ createMiscComponents(); - satsystem::initAcsSubsystem(); + satsystem::init(); } diff --git a/common/config/commonObjects.h b/common/config/commonObjects.h index 4dac8cec..25b83e80 100644 --- a/common/config/commonObjects.h +++ b/common/config/commonObjects.h @@ -57,6 +57,7 @@ enum commonObjects : uint32_t { PLOC_MPSOC_HANDLER = 0x44330015, PLOC_SUPERVISOR_HANDLER = 0x44330016, PLOC_SUPERVISOR_HELPER = 0x44330017, + SCEX_HANDLER = 0x44400000, SOLAR_ARRAY_DEPL_HANDLER = 0x444100A2, HEATER_HANDLER = 0x444100A4, From aa86bc722f0aecc8deee2fbafa2b713d20a64f73 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 29 Aug 2022 15:56:18 +0200 Subject: [PATCH 007/176] retval corrections --- bsp_q7s/core/InitMission.cpp | 2 +- mission/system/tree/payloadModeTree.cpp | 2 +- mission/system/tree/util.cpp | 2 +- mission/system/tree/util.h | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index 3aed9bd8..01662b59 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -160,7 +160,7 @@ void initmission::initTasks() { } #endif result = sysTask->addComponent(objects::ACS_SUBSYSTEM); - if (result != HasReturnvaluesIF::RETURN_OK) { + if (result != returnvalue::OK) { initmission::printAddObjectError("ACS_SUBSYSTEM", objects::ACS_SUBSYSTEM); } diff --git a/mission/system/tree/payloadModeTree.cpp b/mission/system/tree/payloadModeTree.cpp index d5779120..cafcd6e3 100644 --- a/mission/system/tree/payloadModeTree.cpp +++ b/mission/system/tree/payloadModeTree.cpp @@ -3,7 +3,7 @@ #include #include #include -#include +#include #include #include "mission/devices/devicedefinitions/payloadPcduDefinitions.h" diff --git a/mission/system/tree/util.cpp b/mission/system/tree/util.cpp index 2a93efd8..176728eb 100644 --- a/mission/system/tree/util.cpp +++ b/mission/system/tree/util.cpp @@ -3,7 +3,7 @@ #include "fsfw/serviceinterface.h" void subsystem::checkInsert(ReturnValue_t result, const char* ctx) { - if (result != HasReturnvaluesIF::RETURN_OK) { + if (result != returnvalue::OK) { sif::warning << "satsystem::checkInsert: Insertion failed at " << ctx << std::endl; } } diff --git a/mission/system/tree/util.h b/mission/system/tree/util.h index 5caf8e6d..da73e3bf 100644 --- a/mission/system/tree/util.h +++ b/mission/system/tree/util.h @@ -1,7 +1,7 @@ #ifndef MISSION_SYSTEM_TREE_UTIL_H_ #define MISSION_SYSTEM_TREE_UTIL_H_ -#include +#include namespace subsystem { From ba70bde3e96945f8260280bde823b95deff98b21 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 3 Nov 2022 20:57:55 +0100 Subject: [PATCH 008/176] small fix --- mission/system/tree/acsModeTree.cpp | 15 --------------- mission/system/tree/payloadModeTree.cpp | 2 +- mission/system/tree/util.cpp | 10 +++++++++- 3 files changed, 10 insertions(+), 17 deletions(-) diff --git a/mission/system/tree/acsModeTree.cpp b/mission/system/tree/acsModeTree.cpp index 32ced828..4e390985 100644 --- a/mission/system/tree/acsModeTree.cpp +++ b/mission/system/tree/acsModeTree.cpp @@ -16,7 +16,6 @@ namespace { // Alias for checker function const auto check = subsystem::checkInsert; -void checkInsert(ReturnValue_t result, const char* ctx); void buildOffSequence(Subsystem* ss, ModeListEntry& eh); void buildDetumbleSequence(Subsystem* ss, ModeListEntry& entryHelper); void buildSafeSequence(Subsystem* ss, ModeListEntry& entryHelper); @@ -25,7 +24,6 @@ void buildIdleChargeSequence(Subsystem* ss, ModeListEntry& entryHelper); void buildTargetPtSequence(Subsystem* ss, ModeListEntry& entryHelper); } // namespace - static const auto OFF = HasModesIF::MODE_OFF; static const auto NML = DeviceHandlerIF::MODE_NORMAL; @@ -390,17 +388,4 @@ void buildTargetPtSequence(Subsystem* ss, ModeListEntry& eh) { ctxc); } -void checkInsert(ReturnValue_t result, const char* ctx) { - if (result != returnvalue::OK) { - sif::warning << "satsystem::checkInsert: Insertion failed at " << ctx; - if (result == mapdefs::KEY_ALREADY_EXISTS) { - sif::warning << ": Key already exists" << std::endl; - } else if (result == mapdefs::MAP_FULL) { - sif::warning << ": Map full" << std::endl; - } else { - sif::warning << std::endl; - } - } -} - } // namespace diff --git a/mission/system/tree/payloadModeTree.cpp b/mission/system/tree/payloadModeTree.cpp index 95368822..f89bd41d 100644 --- a/mission/system/tree/payloadModeTree.cpp +++ b/mission/system/tree/payloadModeTree.cpp @@ -1,11 +1,11 @@ #include "payloadModeTree.h" -#include "eive/objects.h" #include #include #include #include +#include "eive/objects.h" #include "mission/devices/devicedefinitions/payloadPcduDefinitions.h" #include "mission/system/objects/PayloadSubsystem.h" #include "mission/system/objects/definitions.h" diff --git a/mission/system/tree/util.cpp b/mission/system/tree/util.cpp index 176728eb..92a752e7 100644 --- a/mission/system/tree/util.cpp +++ b/mission/system/tree/util.cpp @@ -1,9 +1,17 @@ #include "util.h" +#include "fsfw/container/FixedMap.h" #include "fsfw/serviceinterface.h" void subsystem::checkInsert(ReturnValue_t result, const char* ctx) { if (result != returnvalue::OK) { - sif::warning << "satsystem::checkInsert: Insertion failed at " << ctx << std::endl; + sif::warning << "satsystem::checkInsert: Insertion failed at " << ctx; + if (result == mapdefs::KEY_ALREADY_EXISTS) { + sif::warning << ": Key already exists" << std::endl; + } else if (result == mapdefs::MAP_FULL) { + sif::warning << ": Map full" << std::endl; + } else { + sif::warning << std::endl; + } } } From fe6b13bb8136599005fa02cd2fd3967dc8246e0f Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 3 Nov 2022 22:59:51 +0100 Subject: [PATCH 009/176] start fixing this crap --- bsp_q7s/core/InitMission.cpp | 23 ++++++++++-------- common/config/eive/objects.h | 2 -- mission/system/objects/CMakeLists.txt | 1 + mission/system/objects/CamSwitcher.cpp | 5 ++++ mission/system/objects/CamSwitcher.h | 13 ++++++++++ mission/system/tree/payloadModeTree.cpp | 32 +++++++++++++++---------- tmtc | 2 +- 7 files changed, 53 insertions(+), 25 deletions(-) create mode 100644 mission/system/objects/CamSwitcher.cpp create mode 100644 mission/system/objects/CamSwitcher.h diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index 4423a8fe..4a0dbeff 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -67,12 +67,6 @@ void initmission::initTasks() { void (*missedDeadlineFunc)(void) = nullptr; #endif - PeriodicTaskIF* sysCtrlTask = factory->createPeriodicTask( - "CORE_CTRL", 60, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.4, missedDeadlineFunc); - result = sysCtrlTask->addComponent(objects::CORE_CONTROLLER); - if (result != returnvalue::OK) { - initmission::printAddObjectError("CORE_CTRL", objects::CORE_CONTROLLER); - } #if OBSW_ADD_SA_DEPL == 1 // Could add this to the core controller but the core controller does so many thing that I would // prefer to have the solar array deployment in a seprate task. @@ -84,6 +78,17 @@ void initmission::initTasks() { } #endif + PeriodicTaskIF* sysTask = factory->createPeriodicTask( + "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); + } + result = sysTask->addComponent(objects::PL_SUBSYSTEM); + if (result != returnvalue::OK) { + initmission::printAddObjectError("PL_SUBSYSTEM", objects::PL_SUBSYSTEM); + } + /* TMTC Distribution */ PeriodicTaskIF* tmTcDistributor = factory->createPeriodicTask( "DIST", 45, PeriodicTaskIF::MINIMUM_STACK_SIZE, 0.2, missedDeadlineFunc); @@ -127,9 +132,7 @@ void initmission::initTasks() { initmission::printAddObjectError("CCSDS Handler", objects::CCSDS_HANDLER); } - // Minimal distance between two received TCs amounts to 0.6 seconds - // If a command has not been read before the next one arrives, the old command will be - // overwritten by the PDEC. + // Runs in IRQ mode, frequency does not really matter PeriodicTaskIF* pdecHandlerTask = factory->createPeriodicTask( "PDEC_HANDLER", 75, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc); result = pdecHandlerTask->addComponent(objects::PDEC_HANDLER); @@ -321,7 +324,7 @@ void initmission::initTasks() { pdecHandlerTask->startTask(); #endif /* OBSW_ADD_CCSDS_IP_CORES == 1 */ - sysCtrlTask->startTask(); + sysTask->startTask(); #if OBSW_ADD_SA_DEPL == 1 solarArrayDeplTask->startTask(); #endif diff --git a/common/config/eive/objects.h b/common/config/eive/objects.h index 4aa03c7a..f0c06916 100644 --- a/common/config/eive/objects.h +++ b/common/config/eive/objects.h @@ -127,11 +127,9 @@ enum commonObjects : uint32_t { SUS_BOARD_ASS = 0x73000002, TCS_BOARD_ASS = 0x73000003, RW_ASS = 0x73000004, - PLOC_SWITCHER = 0x73000005, CAM_SWITCHER = 0x73000006, ACS_SUBSYSTEM = 0x73010001, PL_SUBSYSTEM = 0x73010002, - PLOC_SUBSYSTEM = 0x73010003, EIVE_SYSTEM = 0x73010000, CFDP_HANDLER = 0x73000005, CFDP_DISTRIBUTOR = 0x73000006, diff --git a/mission/system/objects/CMakeLists.txt b/mission/system/objects/CMakeLists.txt index 39d7c800..23e97047 100644 --- a/mission/system/objects/CMakeLists.txt +++ b/mission/system/objects/CMakeLists.txt @@ -1,6 +1,7 @@ target_sources( ${LIB_EIVE_MISSION} PRIVATE EiveSystem.cpp + CamSwitcher.cpp AcsSubsystem.cpp ComSubsystem.cpp PayloadSubsystem.cpp diff --git a/mission/system/objects/CamSwitcher.cpp b/mission/system/objects/CamSwitcher.cpp new file mode 100644 index 00000000..459065ce --- /dev/null +++ b/mission/system/objects/CamSwitcher.cpp @@ -0,0 +1,5 @@ +#include "CamSwitcher.h" + +CamSwitcher::CamSwitcher(object_id_t objectId, PowerSwitchIF *pwrSwitcher, + power::Switch_t pwrSwitch) + : PowerSwitcherComponent(objectId, pwrSwitcher, pwrSwitch) {} diff --git a/mission/system/objects/CamSwitcher.h b/mission/system/objects/CamSwitcher.h new file mode 100644 index 00000000..c762d5da --- /dev/null +++ b/mission/system/objects/CamSwitcher.h @@ -0,0 +1,13 @@ +#ifndef MISSION_SYSTEM_OBJECTS_CAMSWITCHER_H_ +#define MISSION_SYSTEM_OBJECTS_CAMSWITCHER_H_ + +#include + +class CamSwitcher : public PowerSwitcherComponent { + public: + CamSwitcher(object_id_t objectId, PowerSwitchIF *pwrSwitcher, power::Switch_t pwrSwitch); + + private: +}; + +#endif /* MISSION_SYSTEM_OBJECTS_CAMSWITCHER_H_ */ diff --git a/mission/system/tree/payloadModeTree.cpp b/mission/system/tree/payloadModeTree.cpp index f89bd41d..0d4e4257 100644 --- a/mission/system/tree/payloadModeTree.cpp +++ b/mission/system/tree/payloadModeTree.cpp @@ -27,7 +27,8 @@ static const auto NML = DeviceHandlerIF::MODE_NORMAL; auto PL_SEQUENCE_OFF = std::make_pair(OFF << 24, FixedArrayList()); auto PL_TABLE_OFF_TGT = std::make_pair((OFF << 24) | 1, FixedArrayList()); -auto PL_TABLE_OFF_TRANS = std::make_pair((OFF << 24) | 2, FixedArrayList()); +auto PL_TABLE_OFF_TRANS_0 = std::make_pair((OFF << 24) | 2, FixedArrayList()); +auto PL_TABLE_OFF_TRANS_1 = std::make_pair((OFF << 24) | 3, FixedArrayList()); auto PL_SEQUENCE_MPSOC_STREAM = std::make_pair(payload::Modes::MPSOC_STREAM << 24, FixedArrayList()); @@ -110,16 +111,21 @@ void initOffSequence(Subsystem* ss, ModeListEntry& eh) { check(ss->addTable(TableEntry(PL_TABLE_OFF_TGT.first, &PL_TABLE_OFF_TGT.second)), ctxc); // Build OFF transition 0 - iht(objects::PLOC_SWITCHER, OFF, 0, PL_TABLE_OFF_TRANS.second); - iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_OFF_TRANS.second); - iht(objects::SCEX, OFF, 0, PL_TABLE_OFF_TRANS.second); - iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_OFF_TRANS.second); - iht(objects::PLOC_SUBSYSTEM, OFF, 0, PL_TABLE_OFF_TRANS.second); - check(ss->addTable(TableEntry(PL_TABLE_OFF_TRANS.first, &PL_TABLE_OFF_TRANS.second)), ctxc); + iht(objects::PLOC_SWITCHER, OFF, 0, PL_TABLE_OFF_TRANS_0.second); + iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_OFF_TRANS_0.second); + iht(objects::SCEX, OFF, 0, PL_TABLE_OFF_TRANS_0.second); + iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_OFF_TRANS_0.second); + iht(objects::PLOC_MPSOC_HANDLER, OFF, 0, PL_TABLE_OFF_TRANS_0.second); + check(ss->addTable(TableEntry(PL_TABLE_OFF_TRANS_0.first, &PL_TABLE_OFF_TRANS_0.second)), ctxc); + + // Build OFF transition 1 + iht(objects::PLOC_SUPERVISOR_HANDLER, OFF, 0, PL_TABLE_OFF_TRANS_1.second); + check(ss->addTable(TableEntry(PL_TABLE_OFF_TRANS_1.first, &PL_TABLE_OFF_TRANS_1.second)), ctxc); // Build OFF sequence ihs(PL_SEQUENCE_OFF.second, PL_TABLE_OFF_TGT.first, 0, false); - ihs(PL_SEQUENCE_OFF.second, PL_TABLE_OFF_TRANS.first, 0, false); + ihs(PL_SEQUENCE_OFF.second, PL_TABLE_OFF_TRANS_0.first, 0, false); + ihs(PL_SEQUENCE_OFF.second, PL_TABLE_OFF_TRANS_1.first, 0, false); check(ss->addSequence( SequenceEntry(PL_SEQUENCE_OFF.first, &PL_SEQUENCE_OFF.second, PL_SEQUENCE_OFF.first)), ctxc); @@ -147,24 +153,26 @@ void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh) { // Build MPSoC stream target // Camera should always be off to prevent a conflict with the MPSoC streaming + // PL PCDU must be on and in normal mode, but this is commanded separately because of the + // number of commands invovled iht(objects::PLPCDU_HANDLER, NML, plpcdu::ALL_ON_SUBMODE, PL_TABLE_MPSOC_STREAM_TGT.second); - iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_MPSOC_STREAM_TGT.second); iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_MPSOC_STREAM_TGT.second); - iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::MPSOC_ON, PL_TABLE_MPSOC_STREAM_TGT.second); + iht(objects::PLOC_MPSOC_HANDLER, NML, 0, PL_TABLE_MPSOC_STREAM_TGT.second); + iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_MPSOC_STREAM_TGT.second); check( ss->addTable(TableEntry(PL_TABLE_MPSOC_STREAM_TGT.first, &PL_TABLE_MPSOC_STREAM_TGT.second)), ctxc); // Build MPSoC stream transition 0 - iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); iht(objects::SCEX, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); + iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_MPSOC_STREAM_TGT.second); check(ss->addTable( TableEntry(PL_TABLE_MPSOC_STREAM_TRANS_0.first, &PL_TABLE_MPSOC_STREAM_TRANS_0.second)), ctxc); // Build MPSoC stream transition 1 - iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::MPSOC_ON, PL_TABLE_MPSOC_STREAM_TRANS_1.second); + iht(objects::PLOC_MPSOC_HANDLER, NML, 0, PL_TABLE_MPSOC_STREAM_TGT.second); check(ss->addTable( TableEntry(PL_TABLE_MPSOC_STREAM_TRANS_1.first, &PL_TABLE_MPSOC_STREAM_TRANS_1.second)), ctxc); diff --git a/tmtc b/tmtc index f62c67a1..f6fab2d4 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit f62c67a11e54b99fdb60dab13e55456f16450951 +Subproject commit f6fab2d44aff98174835c8446fd69c1ff589521b From c8ddf7472c923512f5a7537412504d626ca40382 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 08:30:47 +0100 Subject: [PATCH 010/176] remove PLOC_SWITCHER and PLOC_SUBSYSTEM usage --- mission/system/tree/payloadModeTree.cpp | 24 +++++++++++------------- 1 file changed, 11 insertions(+), 13 deletions(-) diff --git a/mission/system/tree/payloadModeTree.cpp b/mission/system/tree/payloadModeTree.cpp index 0d4e4257..89286947 100644 --- a/mission/system/tree/payloadModeTree.cpp +++ b/mission/system/tree/payloadModeTree.cpp @@ -58,9 +58,9 @@ auto PL_TABLE_SUPV_ONLY_TRANS_1 = std::make_pair((payload::Modes::SUPV_ONLY << 24) | 3, FixedArrayList()); auto PL_SEQUENCE_EARTH_OBSV = - std::make_pair(payload::Modes::EARTH_OBSV << 24, FixedArrayList()); + std::make_pair(payload::Modes::EARTH_OBSV << 24, FixedArrayList()); auto PL_TABLE_EARTH_OBSV_TGT = - std::make_pair((payload::Modes::EARTH_OBSV << 24) | 1, FixedArrayList()); + std::make_pair((payload::Modes::EARTH_OBSV << 24) | 1, FixedArrayList()); auto PL_TABLE_EARTH_OBSV_TRANS_0 = std::make_pair((payload::Modes::EARTH_OBSV << 24) | 2, FixedArrayList()); auto PL_TABLE_EARTH_OBSV_TRANS_1 = @@ -111,7 +111,6 @@ void initOffSequence(Subsystem* ss, ModeListEntry& eh) { check(ss->addTable(TableEntry(PL_TABLE_OFF_TGT.first, &PL_TABLE_OFF_TGT.second)), ctxc); // Build OFF transition 0 - iht(objects::PLOC_SWITCHER, OFF, 0, PL_TABLE_OFF_TRANS_0.second); iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_OFF_TRANS_0.second); iht(objects::SCEX, OFF, 0, PL_TABLE_OFF_TRANS_0.second); iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_OFF_TRANS_0.second); @@ -215,7 +214,7 @@ void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh) { // Build CAM transition 0 // PLOC is actively commanded off here - iht(objects::PLOC_SUBSYSTEM, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); + iht(objects::PLOC_MPSOC_HANDLER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); iht(objects::SCEX, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); check(ss->addTable( @@ -223,7 +222,7 @@ void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh) { ctxc); // Build CAM transition 1 - iht(objects::PLOC_SWITCHER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_1.second); + iht(objects::PLOC_SUPERVISOR_HANDLER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_1.second); check(ss->addTable( TableEntry(PL_TABLE_MPSOC_STREAM_TRANS_1.first, &PL_TABLE_MPSOC_STREAM_TRANS_1.second)), ctxc); @@ -258,20 +257,19 @@ void initPlSpvSequence(Subsystem* ss, ModeListEntry& eh) { }; // Build Payload Supervisor Only target - iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_SUPV_ONLY_TGT.second); - iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::SUPV_ONLY, PL_TABLE_SUPV_ONLY_TGT.second); + iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_SUPV_ONLY_TGT.second); check(ss->addTable(TableEntry(PL_TABLE_SUPV_ONLY_TGT.first, &PL_TABLE_SUPV_ONLY_TGT.second)), ctxc); // Build Payload Supervisor Only transition 0 - iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_SUPV_ONLY_TRANS_0.second); + iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_SUPV_ONLY_TRANS_0.second); iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_SUPV_ONLY_TRANS_0.second); check(ss->addTable( TableEntry(PL_TABLE_SUPV_ONLY_TRANS_0.first, &PL_TABLE_SUPV_ONLY_TRANS_0.second)), ctxc); // Build Payload Supervisor Only transition 1 - iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::SUPV_ONLY, PL_TABLE_SUPV_ONLY_TRANS_1.second); + iht(objects::PLOC_MPSOC_HANDLER, OFF, 0, PL_TABLE_SUPV_ONLY_TRANS_1.second); // Build Payload Supervisor Only Sequence ihs(PL_SEQUENCE_SUPV_ONLY.second, PL_TABLE_SUPV_ONLY_TGT.first, 0, true); @@ -303,15 +301,15 @@ void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh) { }; // Build Earth Observation target - iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_EARTH_OBSV_TGT.second); + iht(objects::PLOC_MPSOC_HANDLER, NML, 0, PL_TABLE_EARTH_OBSV_TGT.second); + iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_EARTH_OBSV_TGT.second); iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_EARTH_OBSV_TGT.second); iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_EARTH_OBSV_TGT.second); - iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::MPSOC_ON, PL_TABLE_EARTH_OBSV_TGT.second); check(ss->addTable(TableEntry(PL_TABLE_EARTH_OBSV_TGT.first, &PL_TABLE_EARTH_OBSV_TGT.second)), ctxc); // Build Earth Observation transition 0 - iht(objects::PLOC_SWITCHER, ON, 0, PL_TABLE_EARTH_OBSV_TRANS_0.second); + iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_EARTH_OBSV_TRANS_0.second); iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_EARTH_OBSV_TRANS_0.second); iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_EARTH_OBSV_TRANS_0.second); check(ss->addTable( @@ -319,7 +317,7 @@ void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh) { ctxc); // Build Earth Observation transition 1 - iht(objects::PLOC_SUBSYSTEM, NML, payload::ploc::MPSOC_ON, PL_TABLE_EARTH_OBSV_TRANS_1.second); + iht(objects::PLOC_MPSOC_HANDLER, NML, 0, PL_TABLE_CAM_STREAM_TRANS_1.second); check(ss->addTable( TableEntry(PL_TABLE_EARTH_OBSV_TRANS_1.first, &PL_TABLE_EARTH_OBSV_TRANS_1.second)), ctxc); From e3c245b99fa8d7aecb4bc04649733ff8446dd282 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 08:37:59 +0100 Subject: [PATCH 011/176] update changelog --- CHANGELOG.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 91fbd0b5..348e7023 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -10,8 +10,9 @@ list yields a list of all related PRs for each release. # [unreleased] -- Add IRQ mode for PDEC handler - PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/310 +- ACS Subsystem. PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/231 +- Payload Subsystem. PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/231 +- Add IRQ mode for PDEC handler. PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/310 - Extended TM funnels to allow multiple TM recipients. PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/312 - DHB: Transitions to normal mode now possible directly, which simplifies subsystem implementations @@ -77,7 +78,6 @@ list yields a list of all related PRs for each release. ## Added -- ACS Subsystem. PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/231 - Dummy components to run OBSW without relying on external hardware PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/266 - Basic Thermal Controller From 1ac9e53b1ff1f902bd345441fe9e83fb2bdb3246 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 09:35:17 +0100 Subject: [PATCH 012/176] add TAS sources --- CMakeLists.txt | 2 +- thirdparty/CMakeLists.txt | 5 + thirdparty/tas/hdlc.c | 80 +++++ thirdparty/tas/hdlc.h | 26 ++ thirdparty/tas/uart.c | 603 ++++++++++++++++++++++++++++++++++++++ thirdparty/tas/uart.h | 124 ++++++++ 6 files changed, 839 insertions(+), 1 deletion(-) create mode 100644 thirdparty/CMakeLists.txt create mode 100644 thirdparty/tas/hdlc.c create mode 100644 thirdparty/tas/hdlc.h create mode 100644 thirdparty/tas/uart.c create mode 100644 thirdparty/tas/uart.h diff --git a/CMakeLists.txt b/CMakeLists.txt index ddf101a4..644b8bcd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -393,7 +393,7 @@ if(EIVE_ADD_JSON_LIB) add_subdirectory(${LIB_JSON_PATH}) endif() -add_subdirectory(thirdparty/rapidcsv) +add_subdirectory(thirdparty) if(EIVE_ADD_LINUX_FILES) add_subdirectory(${LIB_ARCSEC_PATH}) diff --git a/thirdparty/CMakeLists.txt b/thirdparty/CMakeLists.txt new file mode 100644 index 00000000..7455bdae --- /dev/null +++ b/thirdparty/CMakeLists.txt @@ -0,0 +1,5 @@ +if(EIVE_ADD_LINUX_FILES) + add_subdirectory(tas) +endif() + +add_subdirectory(rapidcsv) diff --git a/thirdparty/tas/hdlc.c b/thirdparty/tas/hdlc.c new file mode 100644 index 00000000..0c668073 --- /dev/null +++ b/thirdparty/tas/hdlc.c @@ -0,0 +1,80 @@ +//************************************************************************************** +/*! \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 +#include "hdlc.h" +#include "spacepacket.h" +#include "crc.h" + +static void hdlc_add_byte(uint8_t ch, uint8_t *buff, uint16_t *pos) +{ + uint16_t templen = *pos; + + if ((ch == 0x7E) || + (ch == 0x7D) || + (ch == 0x7C)) + { + buff[templen++] = 0x7D; + ch ^= 0x20; + } + buff[templen++] = ch; + + *pos = templen; +} + +void hdlc_add_framing(uint8_t *src, uint16_t slen, uint8_t *dst, uint16_t *dlen) +{ + uint16_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 + hdlc_add_byte((uint8_t) (crc16 & 0xFF), dst, &tlen); + hdlc_add_byte((uint8_t) ((crc16 >> 8) & 0xFF), dst, &tlen); + + dst[tlen++] = 0x7C; + *dlen = tlen; +} + +void hdlc_remove_framing(uint8_t *src, uint16_t slen, uint8_t *dst, uint16_t *dlen) +{ + uint16_t tlen = 0; + uint16_t ii; + uint8_t bt; + + *dlen = 0; + if (slen == 0) return; + if ((src[tlen] != 0x7E) && (src[slen-1] != 0x7C)) return; + for (ii = 1; ii < slen-1; ii++) + { + bt = *src++; + + if (bt == 0x7D) + { + bt = *src++ ^ 0x20; + } + dst[tlen++] = bt; + } + *dlen = tlen; +} + + diff --git a/thirdparty/tas/hdlc.h b/thirdparty/tas/hdlc.h new file mode 100644 index 00000000..a728c5c5 --- /dev/null +++ b/thirdparty/tas/hdlc.h @@ -0,0 +1,26 @@ +//************************************************************************************** +/*! \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_ + +#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_framing(uint8_t *src, uint16_t slen, uint8_t *dst, uint16_t *dlen); + +void hdlc_remove_framing(uint8_t *src, uint16_t slen, uint8_t *dst, uint16_t *dlen); + +#endif /* LIB_HDLC_H_ */ diff --git a/thirdparty/tas/uart.c b/thirdparty/tas/uart.c new file mode 100644 index 00000000..51ce59d8 --- /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 "uart.h" +#include "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/thirdparty/tas/uart.h b/thirdparty/tas/uart.h new file mode 100644 index 00000000..233a79d6 --- /dev/null +++ b/thirdparty/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 From 5dc41badc3b241ea59b5d777f532531f8d42ea84 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 09:37:14 +0100 Subject: [PATCH 013/176] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index f62c67a1..f6fab2d4 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit f62c67a11e54b99fdb60dab13e55456f16450951 +Subproject commit f6fab2d44aff98174835c8446fd69c1ff589521b From 048cd89053109396dca297053c192c2629207b36 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 09:45:32 +0100 Subject: [PATCH 014/176] use scoped includes --- thirdparty/tas/CMakeLists.txt | 9 ++ thirdparty/tas/crc.c | 195 ++++++++++++++++++++++++++++++++ thirdparty/tas/hdlc.c | 5 +- thirdparty/tas/tas/crc.h | 107 ++++++++++++++++++ thirdparty/tas/{ => tas}/hdlc.h | 0 thirdparty/tas/{ => tas}/uart.h | 0 thirdparty/tas/uart.c | 4 +- 7 files changed, 315 insertions(+), 5 deletions(-) create mode 100644 thirdparty/tas/CMakeLists.txt create mode 100644 thirdparty/tas/crc.c create mode 100644 thirdparty/tas/tas/crc.h rename thirdparty/tas/{ => tas}/hdlc.h (100%) rename thirdparty/tas/{ => tas}/uart.h (100%) 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..15d152b9 --- /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(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 index 0c668073..6debec9c 100644 --- a/thirdparty/tas/hdlc.c +++ b/thirdparty/tas/hdlc.c @@ -10,9 +10,8 @@ */ #include -#include "hdlc.h" -#include "spacepacket.h" -#include "crc.h" +#include "tas/hdlc.h" +#include "tas/crc.h" static void hdlc_add_byte(uint8_t ch, uint8_t *buff, uint16_t *pos) { diff --git a/thirdparty/tas/tas/crc.h b/thirdparty/tas/tas/crc.h new file mode 100644 index 00000000..f92664b2 --- /dev/null +++ b/thirdparty/tas/tas/crc.h @@ -0,0 +1,107 @@ +/*************************************************************************************** +* \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 + +#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(uint8_t *data, uint16_t len); +#endif diff --git a/thirdparty/tas/hdlc.h b/thirdparty/tas/tas/hdlc.h similarity index 100% rename from thirdparty/tas/hdlc.h rename to thirdparty/tas/tas/hdlc.h diff --git a/thirdparty/tas/uart.h b/thirdparty/tas/tas/uart.h similarity index 100% rename from thirdparty/tas/uart.h rename to thirdparty/tas/tas/uart.h diff --git a/thirdparty/tas/uart.c b/thirdparty/tas/uart.c index 51ce59d8..11e118ed 100644 --- a/thirdparty/tas/uart.c +++ b/thirdparty/tas/uart.c @@ -9,8 +9,8 @@ ************************************************************************************** */ -#include "uart.h" -#include "hdlc.h" +#include "tas/uart.h" +#include "tas/hdlc.h" #ifdef HDLC_ENABLE #define HDLC_RX_STATE_IDLE (0u) From de66ac66c6edce8e9fef055958a2639949131712 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 11:08:47 +0100 Subject: [PATCH 015/176] supv helper is a com IF now --- fsfw | 2 +- linux/devices/ScexUartReader.cpp | 17 ++--- linux/devices/ploc/PlocSupervisorHandler.cpp | 2 +- linux/devices/ploc/PlocSupvHelper.cpp | 64 ++++++++++++++++++- linux/devices/ploc/PlocSupvHelper.h | 65 +++++++++++++++++++- 5 files changed, 132 insertions(+), 18 deletions(-) diff --git a/fsfw b/fsfw index 84b9d1ce..672fca51 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 84b9d1ce216c076bdfeeaf1663aa873c7f1c9cff +Subproject commit 672fca5169b017387e58e2ff864913d932c59aa1 diff --git a/linux/devices/ScexUartReader.cpp b/linux/devices/ScexUartReader.cpp index d128fa63..7d632b06 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/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index dcdff2c3..5b4339e9 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -150,7 +150,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, if (size > config::MAX_PATH_SIZE) { return SupvReturnValuesIF::FILENAME_TOO_LONG; } - result = supvHelper->startEventbBufferRequest( + result = supvHelper->startEventBufferRequest( std::string(reinterpret_cast(data), size)); if (result != returnvalue::OK) { return result; diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 186eef6b..24f436aa 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -1,7 +1,9 @@ #include "PlocSupvHelper.h" #include +#include // Contains file controls like O_RDWR #include +#include #include #include @@ -15,11 +17,14 @@ #include "fsfw/tasks/TaskFactory.h" #include "fsfw/timemanager/Countdown.h" +#include "fsfw_hal/linux/uart/helper.h" #include "mission/utility/Filenaming.h" #include "mission/utility/ProgressPrinter.h" #include "mission/utility/Timestamp.h" -PlocSupvHelper::PlocSupvHelper(object_id_t objectId) : SystemObject(objectId) { +using namespace returnvalue; + +PlocSupvHelper::PlocSupvHelper(object_id_t objectId) : SystemObject(objectId), ringBuf(4096, true) { spParams.maxSize = sizeof(commandBuffer); resetSpParams(); } @@ -187,7 +192,7 @@ void PlocSupvHelper::initiateUpdateContinuation() { semaphore.release(); } -ReturnValue_t PlocSupvHelper::startEventbBufferRequest(std::string path) { +ReturnValue_t PlocSupvHelper::startEventBufferRequest(std::string path) { #ifdef XIPHOS_Q7S ReturnValue_t result = FilesystemHelper::checkPath(path); if (result != returnvalue::OK) { @@ -801,3 +806,58 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception(ploc::SpTmReader& reade } void PlocSupvHelper::resetSpParams() { spParams.buf = commandBuffer; } + +ReturnValue_t PlocSupvHelper::initializeInterface(CookieIF* cookie) { + UartCookie* 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 << "ScexUartReader::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); + + // Non-blocking mode, 0.5 seconds timeout + tty.c_cc[VTIME] = 5; + tty.c_cc[VMIN] = 0; + + uart::setBaudrate(tty, uartCookie->getBaudrate()); + if (tcsetattr(serialPort, TCSANOW, &tty) != 0) { + sif::warning << "ScexUartReader::initializeInterface: tcsetattr call failed with error [" + << errno << ", " << strerror(errno) << std::endl; + } + // Flush received and unread data + tcflush(serialPort, TCIOFLUSH); + return OK; +} + +ReturnValue_t PlocSupvHelper::sendMessage(CookieIF* cookie, const uint8_t* sendData, + size_t sendLen) { + return returnvalue::OK; +} + +ReturnValue_t PlocSupvHelper::getSendSuccess(CookieIF* cookie) { return returnvalue::OK; } + +ReturnValue_t PlocSupvHelper::requestReceiveMessage(CookieIF* cookie, size_t requestLen) { + return returnvalue::OK; +} + +ReturnValue_t PlocSupvHelper::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, + size_t* size) { + return returnvalue::OK; +} diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 30152e65..4e1c4c17 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -1,6 +1,9 @@ #ifndef BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_ #define BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_ +#include +#include + #include #include "OBSWConfig.h" @@ -21,7 +24,9 @@ * the supervisor and the OBC. * @author J. Meier */ -class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { +class PlocSupvHelper : public DeviceCommunicationIF, + public SystemObject, + public ExecutableObjectIF { public: static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_SUPV_HELPER; @@ -131,7 +136,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { /** * @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. @@ -181,6 +186,9 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { struct Update update; + 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 @@ -206,6 +214,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { bool terminate = false; + SimpleRingBuffer ringBuf; /** * Communication interface responsible for data transactions between OBC and Supervisor. */ @@ -272,6 +281,58 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { ReturnValue_t handleRemainingExeReport(ploc::SpTmReader& reader); void resetSpParams(); + + /** + * @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; }; #endif /* BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_ */ From 826f4ce29c22a000da949d9a3efa3b6c5dd4f4d2 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 11:16:22 +0100 Subject: [PATCH 016/176] add lock, use generic sem interface --- linux/devices/ploc/PlocSupvHelper.cpp | 16 ++++++++++------ linux/devices/ploc/PlocSupvHelper.h | 3 ++- 2 files changed, 12 insertions(+), 7 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 24f436aa..a7245cc1 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -3,6 +3,7 @@ #include #include // Contains file controls like O_RDWR #include +#include #include #include @@ -27,6 +28,9 @@ using namespace returnvalue; PlocSupvHelper::PlocSupvHelper(object_id_t objectId) : SystemObject(objectId), ringBuf(4096, true) { spParams.maxSize = sizeof(commandBuffer); resetSpParams(); + semaphore = SemaphoreFactory::instance()->createBinarySemaphore(); + semaphore->acquire(); + lock = MutexFactory::instance()->createMutex(); } PlocSupvHelper::~PlocSupvHelper() {} @@ -44,11 +48,11 @@ ReturnValue_t PlocSupvHelper::initialize() { ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { ReturnValue_t result = returnvalue::OK; - semaphore.acquire(); + semaphore->acquire(); while (true) { switch (internalState) { case InternalState::IDLE: { - semaphore.acquire(); + semaphore->acquire(); break; } case InternalState::UPDATE: { @@ -164,7 +168,7 @@ ReturnValue_t PlocSupvHelper::performUpdate(const supv::UpdateParams& params) { update.sequenceCount = params.seqCount; internalState = InternalState::UPDATE; uartComIF->flushUartTxAndRxBuf(comCookie); - semaphore.release(); + semaphore->release(); return result; } @@ -183,13 +187,13 @@ ReturnValue_t PlocSupvHelper::performMemCheck(uint8_t memoryId, uint32_t startAd update.crcShouldBeChecked = checkCrc; internalState = InternalState::CHECK_MEMORY; uartComIF->flushUartTxAndRxBuf(comCookie); - semaphore.release(); + semaphore->release(); return returnvalue::OK; } void PlocSupvHelper::initiateUpdateContinuation() { internalState = InternalState::CONTINUE_UPDATE; - semaphore.release(); + semaphore->release(); } ReturnValue_t PlocSupvHelper::startEventBufferRequest(std::string path) { @@ -205,7 +209,7 @@ ReturnValue_t PlocSupvHelper::startEventBufferRequest(std::string path) { eventBufferReq.path = path; internalState = InternalState::REQUEST_EVENT_BUFFER; uartComIF->flushUartTxAndRxBuf(comCookie); - semaphore.release(); + semaphore->release(); return returnvalue::OK; } diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 4e1c4c17..809dfd5b 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -186,6 +186,8 @@ class PlocSupvHelper : public DeviceCommunicationIF, struct Update update; + SemaphoreIF* semaphore; + MutexIF* lock; int serialPort = 0; struct termios tty = {}; @@ -202,7 +204,6 @@ class PlocSupvHelper : public DeviceCommunicationIF, InternalState internalState = InternalState::IDLE; - BinarySemaphore semaphore; #ifdef XIPHOS_Q7S SdCardManager* sdcMan = nullptr; #endif From d254331b8e5aad89f9708c532ea7d4b7e7d443d5 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 11:34:33 +0100 Subject: [PATCH 017/176] add basic manual UART reading --- linux/devices/ploc/PlocSupvHelper.cpp | 135 +++++++++++++++++--------- linux/devices/ploc/PlocSupvHelper.h | 12 ++- 2 files changed, 100 insertions(+), 47 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index a7245cc1..ac9a3cd3 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -33,7 +33,7 @@ PlocSupvHelper::PlocSupvHelper(object_id_t objectId) : SystemObject(objectId), r lock = MutexFactory::instance()->createMutex(); } -PlocSupvHelper::~PlocSupvHelper() {} +PlocSupvHelper::~PlocSupvHelper() = default; ReturnValue_t PlocSupvHelper::initialize() { #ifdef XIPHOS_Q7S @@ -47,59 +47,102 @@ ReturnValue_t PlocSupvHelper::initialize() { } ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { - ReturnValue_t result = returnvalue::OK; - semaphore->acquire(); + ReturnValue_t result; + lock->lockMutex(); + internalState = InternalState::IDLE; + lock->unlockMutex(); 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); + semaphore->acquire(); + int bytesRead = 0; + while (true) { + bytesRead = read(serialPort, reinterpret_cast(recBuf.data()), + static_cast(recBuf.size())); + if (bytesRead == 0) { + { + MutexGuard mg(lock); + if (internalState == InternalState::FINISH) { + // Flush received and unread data + tcflush(serialPort, TCIOFLUSH); + internalState = InternalState::IDLE; + break; + } } - internalState = InternalState::IDLE; + } else if (bytesRead < 0) { + sif::warning << "ScexUartReader::performOperation: read call failed with error [" << errno + << ", " << strerror(errno) << "]" << std::endl; 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); + } else if (bytesRead >= static_cast(recBuf.size())) { + sif::error << "ScexUartReader::performOperation: Receive buffer too small for " << bytesRead + << " bytes" << std::endl; + } else if (bytesRead > 0) { + if (debugMode) { + sif::info << "Received " << bytesRead + << " bytes from the Solar Cell Experiment:" << std::endl; } - internalState = InternalState::IDLE; - break; + // insert buffer into ring buffer here + // ReturnValue_t result = dleParser.passData(recBuf.data(), bytesRead); + // TODO: Parse ring buffer here } - 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 + lock->lockMutex(); + InternalState currentState = internalState; + lock->unlockMutex(); + switch (currentState) { + case InternalState::IDLE: { break; - } else { - triggerEvent(SUPV_EVENT_BUFFER_REQUEST_FAILED, result); } - internalState = InternalState::IDLE; - 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); + } + MutexGuard mg(lock); + internalState = InternalState::IDLE; + break; + } + case InternalState::CHECK_MEMORY: { + executeFullCheckMemoryCommand(); + MutexGuard mg(lock); + 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); + } + MutexGuard mg(lock); + 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); + } + MutexGuard mg(lock); + internalState = InternalState::IDLE; + break; + } + case InternalState::HANDLER_DRIVEN: { + continue; + } + default: + sif::debug << "PlocSupvHelper::performOperation: Invalid state" << std::endl; + break; } - default: - sif::debug << "PlocSupvHelper::performOperation: Invalid state" << std::endl; - break; } } } diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 809dfd5b..a54b50a6 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -200,13 +200,22 @@ class PlocSupvHelper : public DeviceCommunicationIF, EventBufferRequest eventBufferReq; - enum class InternalState { IDLE, UPDATE, CONTINUE_UPDATE, REQUEST_EVENT_BUFFER, CHECK_MEMORY }; + enum class InternalState { + IDLE, + HANDLER_DRIVEN, + UPDATE, + CONTINUE_UPDATE, + REQUEST_EVENT_BUFFER, + CHECK_MEMORY, + FINISH + }; InternalState internalState = InternalState::IDLE; #ifdef XIPHOS_Q7S SdCardManager* sdcMan = nullptr; #endif + std::array recBuf = {}; uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]{}; SpacePacketCreator creator; ploc::SpTcParams spParams = ploc::SpTcParams(creator); @@ -214,6 +223,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, std::array tmBuf{}; bool terminate = false; + bool debugMode = false; SimpleRingBuffer ringBuf; /** From 6350dbe0e9a428b7bab152599d936a39a0cd23bf Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 11:38:21 +0100 Subject: [PATCH 018/176] now its getting tricky --- linux/devices/ploc/PlocSupvHelper.cpp | 4 +++- linux/devices/ploc/PlocSupvHelper.h | 3 +-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index ac9a3cd3..2f1b874d 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -25,7 +25,8 @@ using namespace returnvalue; -PlocSupvHelper::PlocSupvHelper(object_id_t objectId) : SystemObject(objectId), ringBuf(4096, true) { +PlocSupvHelper::PlocSupvHelper(object_id_t objectId) + : SystemObject(objectId), recRingBuf(4096, true) { spParams.maxSize = sizeof(commandBuffer); resetSpParams(); semaphore = SemaphoreFactory::instance()->createBinarySemaphore(); @@ -79,6 +80,7 @@ ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { sif::info << "Received " << bytesRead << " bytes from the Solar Cell Experiment:" << std::endl; } + recRingBuf.writeData(recBuf.data(), bytesRead); // insert buffer into ring buffer here // ReturnValue_t result = dleParser.passData(recBuf.data(), bytesRead); // TODO: Parse ring buffer here diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index a54b50a6..c0edc4bb 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -216,6 +216,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, SdCardManager* sdcMan = nullptr; #endif std::array recBuf = {}; + SimpleRingBuffer recRingBuf; uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]{}; SpacePacketCreator creator; ploc::SpTcParams spParams = ploc::SpTcParams(creator); @@ -224,8 +225,6 @@ class PlocSupvHelper : public DeviceCommunicationIF, bool terminate = false; bool debugMode = false; - - SimpleRingBuffer ringBuf; /** * Communication interface responsible for data transactions between OBC and Supervisor. */ From 45c95e559e2376ba9a3e41c71ab72e482bcdc728 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 11:53:07 +0100 Subject: [PATCH 019/176] started HDLC ring buffer decoder --- linux/devices/ploc/PlocSupvHelper.cpp | 152 +++++++++++++++++++------- linux/devices/ploc/PlocSupvHelper.h | 28 +++-- 2 files changed, 131 insertions(+), 49 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 2f1b874d..33cf32fe 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -36,6 +36,45 @@ PlocSupvHelper::PlocSupvHelper(object_id_t objectId) PlocSupvHelper::~PlocSupvHelper() = default; +ReturnValue_t PlocSupvHelper::initializeInterface(CookieIF* cookie) { + UartCookie* 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 << "ScexUartReader::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); + + // Non-blocking mode, 0.5 seconds timeout + tty.c_cc[VTIME] = 5; + tty.c_cc[VMIN] = 0; + + uart::setBaudrate(tty, uartCookie->getBaudrate()); + if (tcsetattr(serialPort, TCSANOW, &tty) != 0) { + sif::warning << "ScexUartReader::initializeInterface: tcsetattr call failed with error [" + << errno << ", " << strerror(errno) << std::endl; + } + // Flush received and unread data + tcflush(serialPort, TCIOFLUSH); + return OK; +} + ReturnValue_t PlocSupvHelper::initialize() { #ifdef XIPHOS_Q7S sdcMan = SdCardManager::instance(); @@ -856,45 +895,6 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception(ploc::SpTmReader& reade void PlocSupvHelper::resetSpParams() { spParams.buf = commandBuffer; } -ReturnValue_t PlocSupvHelper::initializeInterface(CookieIF* cookie) { - UartCookie* 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 << "ScexUartReader::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); - - // Non-blocking mode, 0.5 seconds timeout - tty.c_cc[VTIME] = 5; - tty.c_cc[VMIN] = 0; - - uart::setBaudrate(tty, uartCookie->getBaudrate()); - if (tcsetattr(serialPort, TCSANOW, &tty) != 0) { - sif::warning << "ScexUartReader::initializeInterface: tcsetattr call failed with error [" - << errno << ", " << strerror(errno) << std::endl; - } - // Flush received and unread data - tcflush(serialPort, TCIOFLUSH); - return OK; -} - ReturnValue_t PlocSupvHelper::sendMessage(CookieIF* cookie, const uint8_t* sendData, size_t sendLen) { return returnvalue::OK; @@ -910,3 +910,77 @@ ReturnValue_t PlocSupvHelper::readReceivedMessage(CookieIF* cookie, uint8_t** bu size_t* size) { return returnvalue::OK; } + +ReturnValue_t PlocSupvHelper::parseRecRingBufForHdlc() { + 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; + return returnvalue::OK; + // if (result != returnvalue::OK) { + // ErrorInfo info; + // info.res = result; + // setErrorContext(ErrorTypes::RING_BUF_ERROR, info); + // return result; + // } + // bool stxFound = false; + // size_t stxIdx = 0; + // for (size_t vectorIdx = 0; vectorIdx < availableData; vectorIdx++) { + // // handle STX char + // if (encodedBuf.first[vectorIdx] == DleEncoder::STX_CHAR) { + // if (not stxFound) { + // stxFound = true; + // stxIdx = vectorIdx; + // } else { + // // might be lost packet, so we should advance the read pointer + // // without skipping the STX + // readSize = vectorIdx; + // ErrorInfo info; + // setErrorContext(ErrorTypes::CONSECUTIVE_STX_CHARS, info); + // return POSSIBLE_PACKET_LOSS; + // } + // } + // // handle ETX char + // if (encodedBuf.first[vectorIdx] == DleEncoder::ETX_CHAR) { + // if (stxFound) { + // // This is propably a packet, so we decode it. + // size_t decodedLen = 0; + // size_t dummy = 0; + // + // ReturnValue_t result = + // decoder.decode(&encodedBuf.first[stxIdx], availableData - stxIdx, &dummy, + // decodedBuf.first, decodedBuf.second, + //&decodedLen); if (result == returnvalue::OK) { ctx.setType(ContextType::PACKET_FOUND); + // ctx.decodedPacket.first = decodedBuf.first; + // ctx.decodedPacket.second = decodedLen; + // readSize = ++vectorIdx; + // return returnvalue::OK; + // } else { + // // invalid packet, skip. + // readSize = ++vectorIdx; + // ErrorInfo info; + // info.res = result; + // setErrorContext(ErrorTypes::DECODE_ERROR, info); + // return POSSIBLE_PACKET_LOSS; + // } + // } else { + // // might be lost packet, so we should advance the read pointer + // readSize = ++vectorIdx; + // ErrorInfo info; + // info.len = 0; + // setErrorContext(ErrorTypes::CONSECUTIVE_ETX_CHARS, info); + // return POSSIBLE_PACKET_LOSS; + // } + // } + // } + // return NO_PACKET_FOUND; +} diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index c0edc4bb..8c4bb8e2 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -28,6 +28,17 @@ class PlocSupvHelper : 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 @@ -146,17 +157,9 @@ class PlocSupvHelper : public DeviceCommunicationIF, static uint32_t buildProgParams1(uint8_t percent, uint16_t seqCount); 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 NO_PACKET_FOUND = returnvalue::makeCode(1, 0); + static constexpr ReturnValue_t DECODE_BUF_TOO_SMALL = returnvalue::makeCode(1, 1); static const uint16_t CRC16_INIT = 0xFFFF; // Event buffer reply will carry 24 space packets with 1016 bytes and one space packet with // 192 bytes @@ -166,6 +169,9 @@ class PlocSupvHelper : public DeviceCommunicationIF, static const uint32_t CRC_EXECUTION_TIMEOUT = 60000; static const uint32_t PREPARE_UPDATE_EXECUTION_REPORT = 2000; + static constexpr uint8_t HDLC_START_MARKER = 0x7C; + static constexpr uint8_t HDLC_END_MARKER = 0x7E; + struct Update { uint8_t memoryId; uint32_t startAddress; @@ -216,6 +222,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, SdCardManager* sdcMan = nullptr; #endif std::array recBuf = {}; + std::array encodedBuf = {}; SimpleRingBuffer recRingBuf; uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]{}; SpacePacketCreator creator; @@ -239,6 +246,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, void executeFullCheckMemoryCommand(); + ReturnValue_t parseRecRingBufForHdlc(); ReturnValue_t executeUpdate(); ReturnValue_t continueUpdate(); ReturnValue_t updateOperation(); From af0853a42b86d1cb7e3da5e1dc3d5404d17fc152 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 12:04:47 +0100 Subject: [PATCH 020/176] continue HDLC parsing --- linux/devices/ploc/PlocSupvHelper.cpp | 57 ++++++++++++--------------- linux/devices/ploc/PlocSupvHelper.h | 25 ++++++------ 2 files changed, 40 insertions(+), 42 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 33cf32fe..5b0c9a7c 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -11,6 +11,7 @@ #include #include "OBSWConfig.h" +#include "tas/hdlc.h" #ifdef XIPHOS_Q7S #include "bsp_q7s/fs/FilesystemHelper.h" #include "bsp_q7s/fs/SdCardManager.h" @@ -911,44 +912,38 @@ ReturnValue_t PlocSupvHelper::readReceivedMessage(CookieIF* cookie, uint8_t** bu return returnvalue::OK; } -ReturnValue_t PlocSupvHelper::parseRecRingBufForHdlc() { +ReturnValue_t PlocSupvHelper::parseRecRingBufForHdlc(size_t& readSize) { size_t availableData = recRingBuf.getAvailableReadData(); if (availableData == 0) { - return NO_PACKET_FOUND; + return NO_PACKET_FOUND; } - if(availableData > encodedBuf.size()) { - return DECODE_BUF_TOO_SMALL; + if (availableData > encodedBuf.size()) { + return DECODE_BUF_TOO_SMALL; } ReturnValue_t result = recRingBuf.readData(encodedBuf.data(), availableData); - if(result != returnvalue::OK) { - return result; + if (result != returnvalue::OK) { + return result; } bool startMarkerFound = false; size_t startIdx = 0; return returnvalue::OK; - // if (result != returnvalue::OK) { - // ErrorInfo info; - // info.res = result; - // setErrorContext(ErrorTypes::RING_BUF_ERROR, info); - // return result; - // } - // bool stxFound = false; - // size_t stxIdx = 0; - // for (size_t vectorIdx = 0; vectorIdx < availableData; vectorIdx++) { - // // handle STX char - // if (encodedBuf.first[vectorIdx] == DleEncoder::STX_CHAR) { - // if (not stxFound) { - // stxFound = true; - // stxIdx = vectorIdx; - // } else { - // // might be lost packet, so we should advance the read pointer - // // without skipping the STX - // readSize = vectorIdx; - // ErrorInfo info; - // setErrorContext(ErrorTypes::CONSECUTIVE_STX_CHARS, info); - // return POSSIBLE_PACKET_LOSS; - // } - // } + 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 + } + } + } // // handle ETX char // if (encodedBuf.first[vectorIdx] == DleEncoder::ETX_CHAR) { // if (stxFound) { @@ -959,8 +954,8 @@ ReturnValue_t PlocSupvHelper::parseRecRingBufForHdlc() { // ReturnValue_t result = // decoder.decode(&encodedBuf.first[stxIdx], availableData - stxIdx, &dummy, // decodedBuf.first, decodedBuf.second, - //&decodedLen); if (result == returnvalue::OK) { ctx.setType(ContextType::PACKET_FOUND); - // ctx.decodedPacket.first = decodedBuf.first; + //&decodedLen); if (result == returnvalue::OK) { + //ctx.setType(ContextType::PACKET_FOUND); ctx.decodedPacket.first = decodedBuf.first; // ctx.decodedPacket.second = decodedLen; // readSize = ++vectorIdx; // return returnvalue::OK; diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 8c4bb8e2..38f7869b 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -28,16 +28,16 @@ class PlocSupvHelper : public DeviceCommunicationIF, public SystemObject, public ExecutableObjectIF { public: - static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_SUPV_HELPER; + 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); + //! [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; @@ -157,9 +157,12 @@ class PlocSupvHelper : public DeviceCommunicationIF, static uint32_t buildProgParams1(uint8_t percent, uint16_t seqCount); private: - static constexpr ReturnValue_t NO_PACKET_FOUND = returnvalue::makeCode(1, 0); static constexpr ReturnValue_t DECODE_BUF_TOO_SMALL = returnvalue::makeCode(1, 1); + static constexpr ReturnValue_t POSSIBLE_PACKET_LOSS_CONSECUTIVE_START = + returnvalue::makeCode(1, 2); + static constexpr ReturnValue_t POSSIBLE_PACKET_LOSS_CONSECUTIVE_END = returnvalue::makeCode(1, 3); + static const uint16_t CRC16_INIT = 0xFFFF; // Event buffer reply will carry 24 space packets with 1016 bytes and one space packet with // 192 bytes @@ -246,7 +249,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, void executeFullCheckMemoryCommand(); - ReturnValue_t parseRecRingBufForHdlc(); + ReturnValue_t parseRecRingBufForHdlc(size_t& readSize); ReturnValue_t executeUpdate(); ReturnValue_t continueUpdate(); ReturnValue_t updateOperation(); From b5cd873f6d97ee275429a3eebeebeba890f55e04 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 12:38:30 +0100 Subject: [PATCH 021/176] completed ring buffer parser --- linux/devices/ploc/PlocSupvHelper.cpp | 42 +++++---------------------- linux/devices/ploc/PlocSupvHelper.h | 1 + thirdparty/tas/crc.c | 2 +- thirdparty/tas/hdlc.c | 7 +++-- thirdparty/tas/tas/crc.h | 2 +- thirdparty/tas/tas/hdlc.h | 15 ++++++++-- 6 files changed, 28 insertions(+), 41 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 5b0c9a7c..f4d25707 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -941,41 +941,15 @@ ReturnValue_t PlocSupvHelper::parseRecRingBufForHdlc(size_t& readSize) { if (encodedBuf[idx] == HDLC_END_MARKER) { if (startMarkerFound) { // Probably a packet, so decode it + size_t decodedLen = 0; + hdlc_remove_framing(encodedBuf.data() + startIdx, idx + 1, decodedBuf.data(), &decodedLen); + readSize = decodedLen; + return returnvalue::OK; + } else { + readSize = ++idx; + return POSSIBLE_PACKET_LOSS_CONSECUTIVE_END; } } } - // // handle ETX char - // if (encodedBuf.first[vectorIdx] == DleEncoder::ETX_CHAR) { - // if (stxFound) { - // // This is propably a packet, so we decode it. - // size_t decodedLen = 0; - // size_t dummy = 0; - // - // ReturnValue_t result = - // decoder.decode(&encodedBuf.first[stxIdx], availableData - stxIdx, &dummy, - // decodedBuf.first, decodedBuf.second, - //&decodedLen); if (result == returnvalue::OK) { - //ctx.setType(ContextType::PACKET_FOUND); ctx.decodedPacket.first = decodedBuf.first; - // ctx.decodedPacket.second = decodedLen; - // readSize = ++vectorIdx; - // return returnvalue::OK; - // } else { - // // invalid packet, skip. - // readSize = ++vectorIdx; - // ErrorInfo info; - // info.res = result; - // setErrorContext(ErrorTypes::DECODE_ERROR, info); - // return POSSIBLE_PACKET_LOSS; - // } - // } else { - // // might be lost packet, so we should advance the read pointer - // readSize = ++vectorIdx; - // ErrorInfo info; - // info.len = 0; - // setErrorContext(ErrorTypes::CONSECUTIVE_ETX_CHARS, info); - // return POSSIBLE_PACKET_LOSS; - // } - // } - // } - // return NO_PACKET_FOUND; + return NO_PACKET_FOUND; } diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 38f7869b..b07e120c 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -226,6 +226,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, #endif std::array recBuf = {}; std::array encodedBuf = {}; + std::array decodedBuf = {}; SimpleRingBuffer recRingBuf; uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]{}; SpacePacketCreator creator; diff --git a/thirdparty/tas/crc.c b/thirdparty/tas/crc.c index 15d152b9..5a50a3a8 100644 --- a/thirdparty/tas/crc.c +++ b/thirdparty/tas/crc.c @@ -181,7 +181,7 @@ void calc_crc16_byte_reflected(uint16_t *crc16, uint8_t bt) } // initial: 0xFFFF, xorOut: 0xFFFF, RefIn: true, RefOut: true, polynomial: 0x1021 -uint16_t calc_crc16_buff_reflected(uint8_t *data, uint16_t len) +uint16_t calc_crc16_buff_reflected(const uint8_t *data, uint16_t len) { uint16_t crc16 = 0xFFFF; diff --git a/thirdparty/tas/hdlc.c b/thirdparty/tas/hdlc.c index 6debec9c..4734c0b9 100644 --- a/thirdparty/tas/hdlc.c +++ b/thirdparty/tas/hdlc.c @@ -9,10 +9,11 @@ ************************************************************************************** */ -#include #include "tas/hdlc.h" #include "tas/crc.h" +#include + static void hdlc_add_byte(uint8_t ch, uint8_t *buff, uint16_t *pos) { uint16_t templen = *pos; @@ -29,7 +30,7 @@ static void hdlc_add_byte(uint8_t ch, uint8_t *buff, uint16_t *pos) *pos = templen; } -void hdlc_add_framing(uint8_t *src, uint16_t slen, uint8_t *dst, uint16_t *dlen) +void hdlc_add_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen) { uint16_t tlen = 0; uint16_t ii; @@ -54,7 +55,7 @@ void hdlc_add_framing(uint8_t *src, uint16_t slen, uint8_t *dst, uint16_t *dlen) *dlen = tlen; } -void hdlc_remove_framing(uint8_t *src, uint16_t slen, uint8_t *dst, uint16_t *dlen) +void hdlc_remove_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen) { uint16_t tlen = 0; uint16_t ii; diff --git a/thirdparty/tas/tas/crc.h b/thirdparty/tas/tas/crc.h index f92664b2..a9735402 100644 --- a/thirdparty/tas/tas/crc.h +++ b/thirdparty/tas/tas/crc.h @@ -103,5 +103,5 @@ void calc_crc16_byte_reflected(uint16_t *crc16, uint8_t bt); * \param final_xor The value that the final result will be xored * \return CRC result */ -uint16_t calc_crc16_buff_reflected(uint8_t *data, uint16_t len); +uint16_t calc_crc16_buff_reflected(const uint8_t *data, uint16_t len); #endif diff --git a/thirdparty/tas/tas/hdlc.h b/thirdparty/tas/tas/hdlc.h index a728c5c5..97e69500 100644 --- a/thirdparty/tas/tas/hdlc.h +++ b/thirdparty/tas/tas/hdlc.h @@ -12,6 +12,13 @@ #ifndef LIB_HDLC_H_ #define LIB_HDLC_H_ +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include + #define HDLC_ENABLE #define HDLC_START_BYTE (0x7Eu) @@ -19,8 +26,12 @@ #define HDLC_END_BYTE (0x7Cu) #define HDLC_ESCAPE_CHAR (0x20u) -void hdlc_add_framing(uint8_t *src, uint16_t slen, uint8_t *dst, uint16_t *dlen); +void hdlc_add_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen); -void hdlc_remove_framing(uint8_t *src, uint16_t slen, uint8_t *dst, uint16_t *dlen); +void hdlc_remove_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen); + +#ifdef __cplusplus +} +#endif #endif /* LIB_HDLC_H_ */ From 74837753bfe05beee3e90a005730a958a9ad7699 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 12:45:20 +0100 Subject: [PATCH 022/176] add IPC ring buf and buffer --- linux/devices/ploc/PlocSupvHelper.cpp | 4 +++- linux/devices/ploc/PlocSupvHelper.h | 8 +++++++- 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index f4d25707..371da37d 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -27,7 +27,9 @@ using namespace returnvalue; PlocSupvHelper::PlocSupvHelper(object_id_t objectId) - : SystemObject(objectId), recRingBuf(4096, true) { + : SystemObject(objectId), + recRingBuf(4096, true), + ipcRingBuf(1200 * MAX_STORED_DECODED_PACKETS, true) { spParams.maxSize = sizeof(commandBuffer); resetSpParams(); semaphore = SemaphoreFactory::instance()->createBinarySemaphore(); diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index b07e120c..8a693460 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -7,6 +7,7 @@ #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" @@ -172,6 +173,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, 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 = 0x7C; static constexpr uint8_t HDLC_END_MARKER = 0x7E; @@ -224,10 +226,14 @@ class PlocSupvHelper : public DeviceCommunicationIF, #ifdef XIPHOS_Q7S SdCardManager* sdcMan = nullptr; #endif + SimpleRingBuffer recRingBuf; std::array recBuf = {}; std::array encodedBuf = {}; std::array decodedBuf = {}; - SimpleRingBuffer recRingBuf; + std::array ipcBuffer = {}; + SimpleRingBuffer ipcRingBuf; + FIFO ipcQueue; + uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]{}; SpacePacketCreator creator; ploc::SpTcParams spParams = ploc::SpTcParams(creator); From 5df45f9fa79802b63f52ba847575dd4566f13bcd Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 12:51:01 +0100 Subject: [PATCH 023/176] start com IF function impl --- linux/devices/ploc/PlocSupvHelper.cpp | 60 ++++++++++++++++++++------- linux/devices/ploc/PlocSupvHelper.h | 10 ++--- 2 files changed, 49 insertions(+), 21 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 371da37d..9dd53535 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -92,7 +92,7 @@ ReturnValue_t PlocSupvHelper::initialize() { ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { ReturnValue_t result; lock->lockMutex(); - internalState = InternalState::IDLE; + state = InternalState::IDLE; lock->unlockMutex(); while (true) { semaphore->acquire(); @@ -103,10 +103,10 @@ ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { if (bytesRead == 0) { { MutexGuard mg(lock); - if (internalState == InternalState::FINISH) { + if (state == InternalState::FINISH) { // Flush received and unread data tcflush(serialPort, TCIOFLUSH); - internalState = InternalState::IDLE; + state = InternalState::IDLE; break; } } @@ -128,7 +128,7 @@ ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { // TODO: Parse ring buffer here } lock->lockMutex(); - InternalState currentState = internalState; + InternalState currentState = state; lock->unlockMutex(); switch (currentState) { case InternalState::IDLE: { @@ -144,13 +144,13 @@ ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { triggerEvent(SUPV_UPDATE_FAILED, result); } MutexGuard mg(lock); - internalState = InternalState::IDLE; + state = InternalState::IDLE; break; } case InternalState::CHECK_MEMORY: { executeFullCheckMemoryCommand(); MutexGuard mg(lock); - internalState = InternalState::IDLE; + state = InternalState::IDLE; break; } case InternalState::CONTINUE_UPDATE: { @@ -163,7 +163,7 @@ ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { triggerEvent(SUPV_CONTINUE_UPDATE_FAILED, result); } MutexGuard mg(lock); - internalState = InternalState::IDLE; + state = InternalState::IDLE; break; } case InternalState::REQUEST_EVENT_BUFFER: { @@ -177,7 +177,7 @@ ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { triggerEvent(SUPV_EVENT_BUFFER_REQUEST_FAILED, result); } MutexGuard mg(lock); - internalState = InternalState::IDLE; + state = InternalState::IDLE; break; } case InternalState::HANDLER_DRIVEN: { @@ -253,7 +253,7 @@ ReturnValue_t PlocSupvHelper::performUpdate(const supv::UpdateParams& params) { update.packetNum = 1; update.deleteMemory = params.deleteMemory; update.sequenceCount = params.seqCount; - internalState = InternalState::UPDATE; + state = InternalState::UPDATE; uartComIF->flushUartTxAndRxBuf(comCookie); semaphore->release(); return result; @@ -272,14 +272,14 @@ ReturnValue_t PlocSupvHelper::performMemCheck(uint8_t memoryId, uint32_t startAd update.startAddress = startAddress; update.length = sizeToCheck; update.crcShouldBeChecked = checkCrc; - internalState = InternalState::CHECK_MEMORY; + state = InternalState::CHECK_MEMORY; uartComIF->flushUartTxAndRxBuf(comCookie); semaphore->release(); return returnvalue::OK; } void PlocSupvHelper::initiateUpdateContinuation() { - internalState = InternalState::CONTINUE_UPDATE; + state = InternalState::CONTINUE_UPDATE; semaphore->release(); } @@ -294,7 +294,7 @@ ReturnValue_t PlocSupvHelper::startEventBufferRequest(std::string path) { return PATH_NOT_EXISTS; } eventBufferReq.path = path; - internalState = InternalState::REQUEST_EVENT_BUFFER; + state = InternalState::REQUEST_EVENT_BUFFER; uartComIF->flushUartTxAndRxBuf(comCookie); semaphore->release(); return returnvalue::OK; @@ -584,7 +584,7 @@ ReturnValue_t PlocSupvHelper::sendCommand(ploc::SpTcBase& packet) { 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)); + triggerEvent(SUPV_SENDING_COMMAND_FAILED, result, static_cast(state)); return result; } return result; @@ -699,13 +699,13 @@ ReturnValue_t PlocSupvHelper::receive(uint8_t* data, size_t* readBytes, size_t r 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))); + static_cast(static_cast(state))); 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)); + triggerEvent(SUPV_HELPER_READING_REPLY_FAILED, result, static_cast(state)); return returnvalue::FAILED; } if (*readBytes > 0) { @@ -900,6 +900,23 @@ void PlocSupvHelper::resetSpParams() { spParams.buf = commandBuffer; } ReturnValue_t PlocSupvHelper::sendMessage(CookieIF* cookie, const uint8_t* sendData, size_t sendLen) { + ReturnValue_t result; + if (sendData == nullptr or sendLen == 0) { + return FAILED; + } + lock->lockMutex(); + if (state != InternalState::IDLE) { + lock->unlockMutex(); + return FAILED; + } + tcflush(serialPort, TCIFLUSH); + state = InternalState::RUNNING; + lock->unlockMutex(); + + result = semaphore->release(); + if (result != OK) { + std::cout << "PlocSupvHelper::sendMessage: Releasing semaphore failed" << std::endl; + } return returnvalue::OK; } @@ -911,7 +928,18 @@ ReturnValue_t PlocSupvHelper::requestReceiveMessage(CookieIF* cookie, size_t req ReturnValue_t PlocSupvHelper::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) { - return returnvalue::OK; + MutexGuard mg(lock); + 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 << "ScexUartReader::readReceivedMessage: Reading RingBuffer failed" << std::endl; + } + return OK; } ReturnValue_t PlocSupvHelper::parseRecRingBufForHdlc(size_t& readSize) { diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 8a693460..2e6db05b 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -211,17 +211,17 @@ class PlocSupvHelper : public DeviceCommunicationIF, EventBufferRequest eventBufferReq; - enum class InternalState { - IDLE, + enum class InternalState { IDLE, RUNNING, FINISH }; + + enum class Request { HANDLER_DRIVEN, UPDATE, CONTINUE_UPDATE, REQUEST_EVENT_BUFFER, CHECK_MEMORY, - FINISH }; - - InternalState internalState = InternalState::IDLE; + InternalState state = InternalState::IDLE; + Request request = Request::HANDLER_DRIVEN; #ifdef XIPHOS_Q7S SdCardManager* sdcMan = nullptr; From dc024e5385c2ee29a26db4f43c42899230791f5e Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 13:40:42 +0100 Subject: [PATCH 024/176] low level impl complete --- linux/devices/ploc/PlocSupvHelper.cpp | 218 ++++++++++++++++---------- linux/devices/ploc/PlocSupvHelper.h | 6 + 2 files changed, 142 insertions(+), 82 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 9dd53535..51b6397e 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -90,107 +90,76 @@ ReturnValue_t PlocSupvHelper::initialize() { } ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { - ReturnValue_t result; lock->lockMutex(); state = InternalState::IDLE; lock->unlockMutex(); + bool putTaskToSleep = false; while (true) { semaphore->acquire(); - int bytesRead = 0; while (true) { - bytesRead = read(serialPort, reinterpret_cast(recBuf.data()), - static_cast(recBuf.size())); - if (bytesRead == 0) { - { - MutexGuard mg(lock); - if (state == InternalState::FINISH) { - // Flush received and unread data - tcflush(serialPort, TCIOFLUSH); - state = InternalState::IDLE; - break; - } - } - } else if (bytesRead < 0) { - sif::warning << "ScexUartReader::performOperation: read call failed with error [" << errno - << ", " << strerror(errno) << "]" << std::endl; + putTaskToSleep = handleUartReception(); + if (putTaskToSleep) { break; - } else if (bytesRead >= static_cast(recBuf.size())) { - sif::error << "ScexUartReader::performOperation: Receive buffer too small for " << bytesRead - << " bytes" << std::endl; - } else if (bytesRead > 0) { - if (debugMode) { - sif::info << "Received " << bytesRead - << " bytes from the Solar Cell Experiment:" << std::endl; - } - recRingBuf.writeData(recBuf.data(), bytesRead); - // insert buffer into ring buffer here - // ReturnValue_t result = dleParser.passData(recBuf.data(), bytesRead); - // TODO: Parse ring buffer here } lock->lockMutex(); InternalState currentState = state; lock->unlockMutex(); switch (currentState) { case InternalState::IDLE: { + putTaskToSleep = true; 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); - } - MutexGuard mg(lock); + case InternalState::FINISH: { state = InternalState::IDLE; + putTaskToSleep = true; break; } - case InternalState::CHECK_MEMORY: { - executeFullCheckMemoryCommand(); - MutexGuard mg(lock); - state = InternalState::IDLE; + case InternalState::RUNNING: { + putTaskToSleep = handleRunningRequest(); 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); - } - MutexGuard mg(lock); - state = 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); - } - MutexGuard mg(lock); - state = InternalState::IDLE; - break; - } - case InternalState::HANDLER_DRIVEN: { - continue; - } - default: - sif::debug << "PlocSupvHelper::performOperation: Invalid state" << std::endl; - break; + } + if (putTaskToSleep) { + break; } } } } +bool PlocSupvHelper::handleUartReception() { + ReturnValue_t result = OK; + ssize_t bytesRead = read(serialPort, reinterpret_cast(recBuf.data()), + static_cast(recBuf.size())); + if (bytesRead == 0) { + { + MutexGuard mg(lock); + if (state == InternalState::FINISH) { + // Flush received and unread data + tcflush(serialPort, TCIOFLUSH); + state = InternalState::IDLE; + return true; + } + } + while (result != NO_PACKET_FOUND) { + result = tryHdlcParsing(); + } + } else if (bytesRead < 0) { + sif::warning << "PlocSupvHelper::performOperation: read call failed with error [" << errno + << ", " << strerror(errno) << "]" << std::endl; + return true; + } else if (bytesRead >= static_cast(recBuf.size())) { + sif::error << "PlocSupvHelper::performOperation: Receive buffer too small for " << bytesRead + << " bytes" << std::endl; + } else if (bytesRead > 0) { + if (debugMode) { + sif::info << "Received " << bytesRead << " bytes from the PLOC Supervisor:" << std::endl; + } + recRingBuf.writeData(recBuf.data(), bytesRead); + tryHdlcParsing(); + } + return false; +} + ReturnValue_t PlocSupvHelper::setComIF(UartComIF* uartComIF_) { if (uartComIF_ == nullptr) { sif::warning << "PlocSupvHelper::initialize: Provided invalid uart com if" << std::endl; @@ -253,7 +222,7 @@ ReturnValue_t PlocSupvHelper::performUpdate(const supv::UpdateParams& params) { update.packetNum = 1; update.deleteMemory = params.deleteMemory; update.sequenceCount = params.seqCount; - state = InternalState::UPDATE; + request = Request::UPDATE; uartComIF->flushUartTxAndRxBuf(comCookie); semaphore->release(); return result; @@ -272,14 +241,14 @@ ReturnValue_t PlocSupvHelper::performMemCheck(uint8_t memoryId, uint32_t startAd update.startAddress = startAddress; update.length = sizeToCheck; update.crcShouldBeChecked = checkCrc; - state = InternalState::CHECK_MEMORY; + request = Request::CHECK_MEMORY; uartComIF->flushUartTxAndRxBuf(comCookie); semaphore->release(); return returnvalue::OK; } void PlocSupvHelper::initiateUpdateContinuation() { - state = InternalState::CONTINUE_UPDATE; + request = Request::CONTINUE_UPDATE; semaphore->release(); } @@ -294,7 +263,7 @@ ReturnValue_t PlocSupvHelper::startEventBufferRequest(std::string path) { return PATH_NOT_EXISTS; } eventBufferReq.path = path; - state = InternalState::REQUEST_EVENT_BUFFER; + request = Request::REQUEST_EVENT_BUFFER; uartComIF->flushUartTxAndRxBuf(comCookie); semaphore->release(); return returnvalue::OK; @@ -917,7 +886,7 @@ ReturnValue_t PlocSupvHelper::sendMessage(CookieIF* cookie, const uint8_t* sendD if (result != OK) { std::cout << "PlocSupvHelper::sendMessage: Releasing semaphore failed" << std::endl; } - return returnvalue::OK; + return encodeAndSendPacket(sendData, sendLen); } ReturnValue_t PlocSupvHelper::getSendSuccess(CookieIF* cookie) { return returnvalue::OK; } @@ -926,6 +895,74 @@ ReturnValue_t PlocSupvHelper::requestReceiveMessage(CookieIF* cookie, size_t req return returnvalue::OK; } +bool PlocSupvHelper::handleRunningRequest() { + 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); + } + MutexGuard mg(lock); + state = InternalState::IDLE; + return true; + } + case Request::CHECK_MEMORY: { + executeFullCheckMemoryCommand(); + MutexGuard mg(lock); + state = InternalState::IDLE; + return true; + } + 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); + } + MutexGuard mg(lock); + state = InternalState::IDLE; + return true; + } + 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); + } + MutexGuard mg(lock); + state = InternalState::IDLE; + return true; + } + case Request::HANDLER_DRIVEN: { + break; + } + } + return false; +} + +ReturnValue_t PlocSupvHelper::encodeAndSendPacket(const uint8_t* sendData, size_t sendLen) { + size_t encodedLen = 0; + hdlc_add_framing(sendData, sendLen, sendBuf.data(), &encodedLen); + size_t bytesWritten = write(serialPort, sendBuf.data(), encodedLen); + if (bytesWritten != encodedLen) { + sif::warning << "ScexUartReader::sendMessage: Sending ping command to solar experiment failed" + << std::endl; + return FAILED; + } + return returnvalue::OK; +} + ReturnValue_t PlocSupvHelper::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) { MutexGuard mg(lock); @@ -937,11 +974,28 @@ ReturnValue_t PlocSupvHelper::readReceivedMessage(CookieIF* cookie, uint8_t** bu *buffer = ipcBuffer.data(); ReturnValue_t result = ipcRingBuf.readData(ipcBuffer.data(), *size, true); if (result != OK) { - sif::warning << "ScexUartReader::readReceivedMessage: Reading RingBuffer failed" << std::endl; + sif::warning << "PlocSupvHelper::readReceivedMessage: Reading RingBuffer failed" << std::endl; } return OK; } +ReturnValue_t PlocSupvHelper::tryHdlcParsing() { + size_t bytesRead = 0; + ReturnValue_t result = parseRecRingBufForHdlc(bytesRead); + if (result == returnvalue::OK) { + // Packet found, advance read pointer. + ipcRingBuf.writeData(decodedBuf.data(), bytesRead); + recRingBuf.deleteData(bytesRead); + } else if (result != NO_PACKET_FOUND) { + sif::warning << "ScexUartReader::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 PlocSupvHelper::parseRecRingBufForHdlc(size_t& readSize) { size_t availableData = recRingBuf.getAvailableReadData(); if (availableData == 0) { diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 2e6db05b..d2a3a3ec 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -227,6 +227,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, SdCardManager* sdcMan = nullptr; #endif SimpleRingBuffer recRingBuf; + std::array sendBuf = {}; std::array recBuf = {}; std::array encodedBuf = {}; std::array decodedBuf = {}; @@ -254,8 +255,13 @@ class PlocSupvHelper : public DeviceCommunicationIF, // Remembers APID to know at which command a procedure failed uint16_t rememberApid = 0; + bool handleRunningRequest(); + bool handleUartReception(); + + ReturnValue_t encodeAndSendPacket(const uint8_t* sendData, size_t sendLen); void executeFullCheckMemoryCommand(); + ReturnValue_t tryHdlcParsing(); ReturnValue_t parseRecRingBufForHdlc(size_t& readSize); ReturnValue_t executeUpdate(); ReturnValue_t continueUpdate(); From 2b9afbedff1783500afda35e37c1e3c4bd7d62cb Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 4 Nov 2022 14:19:58 +0100 Subject: [PATCH 025/176] important fix and clarification --- .../devicedefinitions/PlocMPSoCDefinitions.h | 23 +++--- .../PlocSupervisorDefinitions.h | 75 ++++++++++++------- linux/devices/ploc/PlocSupervisorHandler.cpp | 9 +-- mission/devices/devicedefinitions/SpBase.h | 10 +-- 4 files changed, 68 insertions(+), 49 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index a5ed0672..a373d96b 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.setFullPacketLen(INIT_LENGTH); } ReturnValue_t buildPacket() { return buildPacket(nullptr, 0); } @@ -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.setFullPacketLen(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.setFullPacketLen(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.setFullPacketLen(nameSize + sizeof(NULL_TERMINATOR) + sizeof(accessMode) + CRC_SIZE); ReturnValue_t result = checkPayloadLen(); if (result != returnvalue::OK) { return result; @@ -339,7 +339,7 @@ class FlashFclose : public ploc::SpTcBase { ReturnValue_t createPacket(std::string filename) { size_t nameSize = filename.size(); - spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR)); + spParams.setFullPacketLen(nameSize + sizeof(NULL_TERMINATOR) + CRC_SIZE); ReturnValue_t result = checkPayloadLen(); if (result != returnvalue::OK) { return result; @@ -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.setFullPacketLen(static_cast(writeLen) + 4 + CRC_SIZE); result = checkPayloadLen(); if (result != returnvalue::OK) { return result; @@ -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.setFullPacketLen(nameSize + sizeof(NULL_TERMINATOR) + CRC_SIZE); auto res = checkPayloadLen(); if (res != returnvalue::OK) { return res; @@ -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.setFullPacketLen(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.setFullPacketLen(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.setFullPacketLen(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.setFullPacketLen(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..0e4d30c2 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -161,8 +161,6 @@ 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; - struct UpdateParams { std::string file; uint8_t memId; @@ -284,6 +282,29 @@ static const uint32_t ERASE_MEMORY = 60000; static const uint32_t UPDATE_STATUS_REPORT = 70000; } // namespace recv_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; + +struct SupvTcParams : public ploc::SpTcParams { + public: + SupvTcParams(SpacePacketCreator& creator) : ploc::SpTcParams(creator) {} + + SupvTcParams(SpacePacketCreator& creator, uint8_t* buf, size_t maxSize) + : ploc::SpTcParams(creator, buf, maxSize) {} + + void setLenFromPayloadLen(size_t payloadLen) { + setFullPacketLen(ccsds::HEADER_LEN + SECONDARY_HEADER_LEN + payloadLen + CRC_LEN); + } +}; + +class SupvTcBase : public ploc::SpTcBase { + public: + SupvTcBase(SupvTcParams params) : ploc::SpTcBase(params) {} + + private: +}; + /** * @brief This class creates a space packet containing only the header data and the CRC. */ @@ -297,7 +318,7 @@ class ApidOnlyPacket : public ploc::SpTcBase { * @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.setFullPacketLen(LENGTH_EMPTY_TC); spParams.creator.setApid(apid); } @@ -332,7 +353,7 @@ 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.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SEL_MPSOC_BOOT_IMAGE); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -378,7 +399,7 @@ class EnableNvms : public ploc::SpTcBase { * @param bp2 Partition pin 2 */ EnableNvms(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_ENABLE_NVMS); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -408,7 +429,7 @@ class EnableNvms : public ploc::SpTcBase { class SetTimeRef : public ploc::SpTcBase { public: SetTimeRef(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_TIME_REF); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -487,7 +508,7 @@ class SetBootTimeout : public ploc::SpTcBase { * @param timeout The boot timeout in milliseconds. */ SetBootTimeout(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_BOOT_TIMEOUT); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -524,7 +545,7 @@ class SetRestartTries : public ploc::SpTcBase { * @param restartTries Maximum restart tries to set. */ SetRestartTries(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_MAX_RESTART_TRIES); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -558,7 +579,7 @@ class DisablePeriodicHkTransmission : public ploc::SpTcBase { * @brief Constructor */ DisablePeriodicHkTransmission(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_DISABLE_HK); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -594,7 +615,7 @@ class LatchupAlert : public ploc::SpTcBase { * 3 - 3.3V, 4 - NVM_4XO, 5 - MISSION, 6 - SAFECOTS) */ LatchupAlert(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -632,7 +653,7 @@ class SetAlertlimit : public ploc::SpTcBase { * @param dutycycle */ SetAlertlimit(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ALERT_LIMIT); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -675,7 +696,7 @@ class SetAdcEnabledChannels : public ploc::SpTcBase { * @param ch Defines channels to be enabled or disabled. */ SetAdcEnabledChannels(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ADC_ENABLED_CHANNELS); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -714,7 +735,7 @@ class SetAdcWindowAndStride : public ploc::SpTcBase { * @param stridingStepSize */ SetAdcWindowAndStride(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ADC_WINDOW_AND_STRIDE); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -754,7 +775,7 @@ class SetAdcThreshold : public ploc::SpTcBase { * @param threshold */ SetAdcThreshold(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ADC_THRESHOLD); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -792,7 +813,7 @@ class RunAutoEmTests : public ploc::SpTcBase { * @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.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_RUN_AUTO_EM_TESTS); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -834,7 +855,7 @@ class MramCmd : public ploc::SpTcBase { * @note The content at the stop address is excluded from the dump or wipe operation. */ MramCmd(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -888,7 +909,7 @@ class SetGpio : public ploc::SpTcBase { * @param val */ SetGpio(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_GPIO); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -932,7 +953,7 @@ class ReadGpio : public ploc::SpTcBase { * @param pin */ ReadGpio(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.setFullPacketLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_READ_GPIO); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1009,14 +1030,14 @@ class FactoryReset : public ploc::SpTcBase { default: break; } - spParams.setDataFieldLen(packetDataLen); + spParams.setFullPacketLen(packetDataLen); } }; class SetShutdownTimeout : public ploc::SpTcBase { public: SetShutdownTimeout(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setPayloadLen(PAYLOAD_LEN); + spParams.setFullPacketLen(PAYLOAD_LEN + 2); spParams.creator.setApid(APID_SET_SHUTDOWN_TIMEOUT); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1055,7 +1076,7 @@ class CheckMemory : public ploc::SpTcBase { * @param length Length in bytes of memory region */ CheckMemory(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setPayloadLen(PAYLOAD_LENGTH); + spParams.setFullPacketLen(PAYLOAD_LENGTH + 2); spParams.creator.setApid(APID_CHECK_MEMORY); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1134,9 +1155,9 @@ class WriteMemory : public ploc::SpTcBase { uint8_t* updateData) { uint8_t* data = payloadStart; if (updateDataLen % 2 != 0) { - spParams.setPayloadLen(META_DATA_LENGTH + updateDataLen + 1); + spParams.setFullPacketLen(META_DATA_LENGTH + updateDataLen + 1 + 2); } else { - spParams.setPayloadLen(META_DATA_LENGTH + updateDataLen); + spParams.setFullPacketLen(META_DATA_LENGTH + updateDataLen + 2); } // To avoid crashes in this unexpected case ReturnValue_t result = checkPayloadLen(); @@ -1168,7 +1189,7 @@ class WriteMemory : public ploc::SpTcBase { class EraseMemory : public ploc::SpTcBase { public: EraseMemory(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setPayloadLen(PAYLOAD_LENGTH); + spParams.setFullPacketLen(PAYLOAD_LENGTH + 2); spParams.creator.setApid(APID_ERASE_MEMORY); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1210,7 +1231,7 @@ class EraseMemory : public ploc::SpTcBase { class EnableAutoTm : public ploc::SpTcBase { public: EnableAutoTm(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setPayloadLen(PAYLOAD_LENGTH); + spParams.setFullPacketLen(PAYLOAD_LENGTH + 2); spParams.creator.setApid(APID_AUTO_TM); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1235,7 +1256,7 @@ class EnableAutoTm : public ploc::SpTcBase { class DisableAutoTm : public ploc::SpTcBase { public: DisableAutoTm(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setPayloadLen(PAYLOAD_LENGTH); + spParams.setFullPacketLen(PAYLOAD_LENGTH + 2); spParams.creator.setApid(APID_AUTO_TM); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1270,7 +1291,7 @@ class RequestLoggingData : public ploc::SpTcBase { }; RequestLoggingData(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setPayloadLen(PAYLOAD_LENGTH); + spParams.setFullPacketLen(PAYLOAD_LENGTH + 2); spParams.creator.setApid(APID_REQUEST_LOGGING_DATA); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 5b4339e9..95f64510 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -1808,11 +1808,11 @@ ReturnValue_t PlocSupervisorHandler::parseMramPackets(const uint8_t* packet, siz std::memcpy(spacePacketBuffer + bufferTop, packet + idx, 1); bufferTop += 1; *foundLen += 1; - if (bufferTop >= supv::SPACE_PACKET_HEADER_LENGTH) { + if (bufferTop >= ccsds::HEADER_LEN) { packetLen = readSpacePacketLength(spacePacketBuffer); } - if (bufferTop == supv::SPACE_PACKET_HEADER_LENGTH + packetLen + 1) { + if (bufferTop == ccsds::HEADER_LEN + packetLen + 1) { packetInBuffer = true; bufferTop = 0; return checkMramPacketApid(); @@ -1838,7 +1838,7 @@ ReturnValue_t PlocSupervisorHandler::handleMramDumpPacket(DeviceCommandId_t id) // 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; @@ -1940,8 +1940,7 @@ ReturnValue_t PlocSupervisorHandler::handleMramDumpFile(DeviceCommandId_t id) { return SupvReturnValuesIF::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; } diff --git a/mission/devices/devicedefinitions/SpBase.h b/mission/devices/devicedefinitions/SpBase.h index caa14d5f..edc91334 100644 --- a/mission/devices/devicedefinitions/SpBase.h +++ b/mission/devices/devicedefinitions/SpBase.h @@ -14,14 +14,12 @@ 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 setFullPacketLen(size_t fullPacketLen_) { fullPacketLen = fullPacketLen_; } SpacePacketCreator& creator; uint8_t* buf = nullptr; size_t maxSize = 0; - size_t dataFieldLen = 0; + size_t fullPacketLen = 0; }; class SpTcBase { @@ -39,7 +37,7 @@ class SpTcBase { } void updateSpFields() { - spParams.creator.setDataLenField(spParams.dataFieldLen - 1); + spParams.creator.setDataLenField(spParams.fullPacketLen - 1); spParams.creator.setPacketType(ccsds::PacketType::TC); } @@ -50,7 +48,7 @@ class SpTcBase { uint16_t getApid() const { return spParams.creator.getApid(); } ReturnValue_t checkPayloadLen() { - if (ccsds::HEADER_LEN + spParams.dataFieldLen > spParams.maxSize) { + if (ccsds::HEADER_LEN + spParams.fullPacketLen > spParams.maxSize) { return SerializeIF::BUFFER_TOO_SHORT; } From bb2f8edc7773ac081027067d0bd33e8624eece42 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 7 Nov 2022 09:26:36 +0100 Subject: [PATCH 026/176] add new APID defs --- .../PlocSupervisorDefinitions.h | 80 +++++++++++++++++++ 1 file changed, 80 insertions(+) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 0e4d30c2..3dc2931e 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -15,6 +15,23 @@ namespace supv { +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; + /** Command IDs */ static const DeviceCommandId_t NONE = 0; static const DeviceCommandId_t GET_HK_REPORT = 1; @@ -104,6 +121,64 @@ static const uint16_t APID_DATA_LOGGER_DATA = 0x20D; // 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 constexpr uint16_t APID_TMTC_MAN = 0x00; +static constexpr uint16_t APID_HK = 0x01; +static constexpr uint16_t APID_BOOT_MAN = 0x02; +static constexpr uint16_t APID_LATCHUP_MON = 0x03; +static constexpr uint16_t APID_ADC_MON = 0x04; +static constexpr uint16_t APID_MEM_MAN = 0x05; +static constexpr uint16_t APID_DATA_LOGGER = 0x06; +static constexpr uint16_t APID_WDOG_MAN = 0x07; + +enum class HkServiceIds: uint8_t { + ENABLE = 0x01, + SET_PERIOD = 0x02, + GET_REPORT = 0x03, + GET_HARDFAULTS_REPORT = 0x04, +}; + +enum class TmtcServiceIds: 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 BootManServiceIds: 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 LatchupMonServiceIds: 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 AdcMonServiceIds: uint8_t {}; + +enum class DataLoggerServiceIds: uint8_t { + 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 WdogManServiceIds: uint8_t {}; + 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; @@ -302,6 +377,11 @@ class SupvTcBase : public ploc::SpTcBase { public: SupvTcBase(SupvTcParams params) : ploc::SpTcBase(params) {} + SupvTcBase(SupvTcParams params, uint16_t apid, uint16_t seqCount) + : ploc::SpTcBase(params, apid, seqCount) { + + } + private: }; From 32865d183494019f68a7c8bd8f5778917539cf5c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 7 Nov 2022 10:00:54 +0100 Subject: [PATCH 027/176] use on/off semantics and rename handler --- .../PlocSupervisorDefinitions.h | 59 ++++++++---------- linux/devices/ploc/CMakeLists.txt | 2 +- linux/devices/ploc/PlocSupervisorHandler.h | 3 +- ...PlocSupvHelper.cpp => PlocSupvUartMan.cpp} | 62 +++++++------------ .../{PlocSupvHelper.h => PlocSupvUartMan.h} | 21 ++++--- 5 files changed, 66 insertions(+), 81 deletions(-) rename linux/devices/ploc/{PlocSupvHelper.cpp => PlocSupvUartMan.cpp} (96%) rename linux/devices/ploc/{PlocSupvHelper.h => PlocSupvUartMan.h} (97%) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 3dc2931e..75bbdb28 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -15,21 +15,20 @@ namespace supv { -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 +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 + 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; /** Command IDs */ @@ -130,23 +129,23 @@ static constexpr uint16_t APID_MEM_MAN = 0x05; static constexpr uint16_t APID_DATA_LOGGER = 0x06; static constexpr uint16_t APID_WDOG_MAN = 0x07; -enum class HkServiceIds: uint8_t { +enum class HkServiceIds : uint8_t { ENABLE = 0x01, SET_PERIOD = 0x02, GET_REPORT = 0x03, GET_HARDFAULTS_REPORT = 0x04, }; -enum class TmtcServiceIds: 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 TmtcServiceIds : 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 BootManServiceIds: uint8_t { +enum class BootManServiceIds : uint8_t { START_MPSOC = 0x01, SHUTDOWN_MPSOC = 0x02, SELECT_IMAGE = 0x03, @@ -160,7 +159,7 @@ enum class BootManServiceIds: uint8_t { FACTORY_FLASH = 0x0C }; -enum class LatchupMonServiceIds: uint8_t { +enum class LatchupMonServiceIds : uint8_t { ENABLE = 0x01, DISABLE = 0x02, SET_ALERT_LIMIT = 0x04, @@ -169,15 +168,13 @@ enum class LatchupMonServiceIds: uint8_t { // Right now, none of the commands seem to be implemented, but still // keep the enum here in case some are added -enum class AdcMonServiceIds: uint8_t {}; +enum class AdcMonServiceIds : uint8_t {}; -enum class DataLoggerServiceIds: uint8_t { - FACTORY_RESET = 0x07 -}; +enum class DataLoggerServiceIds : uint8_t { 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 WdogManServiceIds: uint8_t {}; +enum class WdogManServiceIds : uint8_t {}; static const uint16_t APID_START_MPSOC = 0xA1; static const uint16_t APID_SHUTWOWN_MPSOC = 0xA2; @@ -378,9 +375,7 @@ class SupvTcBase : public ploc::SpTcBase { SupvTcBase(SupvTcParams params) : ploc::SpTcBase(params) {} SupvTcBase(SupvTcParams params, uint16_t apid, uint16_t seqCount) - : ploc::SpTcBase(params, apid, seqCount) { - - } + : ploc::SpTcBase(params, apid, seqCount) {} private: }; 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/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 4bdf2efa..d9776c36 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -1,8 +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" diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp similarity index 96% rename from linux/devices/ploc/PlocSupvHelper.cpp rename to linux/devices/ploc/PlocSupvUartMan.cpp index 51b6397e..5bab8d13 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -1,9 +1,8 @@ -#include "PlocSupvHelper.h" - #include #include // Contains file controls like O_RDWR #include #include +#include #include #include @@ -90,36 +89,37 @@ ReturnValue_t PlocSupvHelper::initialize() { } ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { - lock->lockMutex(); - state = InternalState::IDLE; - lock->unlockMutex(); bool putTaskToSleep = false; while (true) { semaphore->acquire(); while (true) { putTaskToSleep = handleUartReception(); if (putTaskToSleep) { + performUartShutdown(); break; } lock->lockMutex(); InternalState currentState = state; lock->unlockMutex(); switch (currentState) { - case InternalState::IDLE: { + case InternalState::SLEEPING: + case InternalState::GO_TO_SLEEP: { putTaskToSleep = true; break; } - case InternalState::FINISH: { - state = InternalState::IDLE; - putTaskToSleep = true; + case InternalState::LONGER_REQUEST: { + if (handleRunningLongerRequest() == REQUEST_DONE) { + MutexGuard mg(lock); + state = InternalState::DEFAULT; + } break; } - case InternalState::RUNNING: { - putTaskToSleep = handleRunningRequest(); + case InternalState::DEFAULT: { break; } } if (putTaskToSleep) { + performUartShutdown(); break; } } @@ -133,10 +133,7 @@ bool PlocSupvHelper::handleUartReception() { if (bytesRead == 0) { { MutexGuard mg(lock); - if (state == InternalState::FINISH) { - // Flush received and unread data - tcflush(serialPort, TCIOFLUSH); - state = InternalState::IDLE; + if (state == InternalState::GO_TO_SLEEP) { return true; } } @@ -869,23 +866,15 @@ void PlocSupvHelper::resetSpParams() { spParams.buf = commandBuffer; } ReturnValue_t PlocSupvHelper::sendMessage(CookieIF* cookie, const uint8_t* sendData, size_t sendLen) { - ReturnValue_t result; if (sendData == nullptr or sendLen == 0) { return FAILED; } lock->lockMutex(); - if (state != InternalState::IDLE) { + if (state == InternalState::SLEEPING or state == InternalState::LONGER_REQUEST) { lock->unlockMutex(); return FAILED; } - tcflush(serialPort, TCIFLUSH); - state = InternalState::RUNNING; lock->unlockMutex(); - - result = semaphore->release(); - if (result != OK) { - std::cout << "PlocSupvHelper::sendMessage: Releasing semaphore failed" << std::endl; - } return encodeAndSendPacket(sendData, sendLen); } @@ -895,7 +884,7 @@ ReturnValue_t PlocSupvHelper::requestReceiveMessage(CookieIF* cookie, size_t req return returnvalue::OK; } -bool PlocSupvHelper::handleRunningRequest() { +ReturnValue_t PlocSupvHelper::handleRunningLongerRequest() { ReturnValue_t result = OK; switch (request) { case Request::UPDATE: { @@ -907,15 +896,11 @@ bool PlocSupvHelper::handleRunningRequest() { } else { triggerEvent(SUPV_UPDATE_FAILED, result); } - MutexGuard mg(lock); - state = InternalState::IDLE; - return true; + break; } case Request::CHECK_MEMORY: { executeFullCheckMemoryCommand(); - MutexGuard mg(lock); - state = InternalState::IDLE; - return true; + break; } case Request::CONTINUE_UPDATE: { result = continueUpdate(); @@ -926,9 +911,7 @@ bool PlocSupvHelper::handleRunningRequest() { } else { triggerEvent(SUPV_CONTINUE_UPDATE_FAILED, result); } - MutexGuard mg(lock); - state = InternalState::IDLE; - return true; + break; } case Request::REQUEST_EVENT_BUFFER: { result = performEventBufferRequest(); @@ -940,11 +923,9 @@ bool PlocSupvHelper::handleRunningRequest() { } else { triggerEvent(SUPV_EVENT_BUFFER_REQUEST_FAILED, result); } - MutexGuard mg(lock); - state = InternalState::IDLE; - return true; + break; } - case Request::HANDLER_DRIVEN: { + case Request::DEFAULT: { break; } } @@ -1037,3 +1018,8 @@ ReturnValue_t PlocSupvHelper::parseRecRingBufForHdlc(size_t& readSize) { } return NO_PACKET_FOUND; } + +void PlocSupvHelper::performUartShutdown() { + tcflush(serialPort, TCIOFLUSH); + state = InternalState::GO_TO_SLEEP; +} diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvUartMan.h similarity index 97% rename from linux/devices/ploc/PlocSupvHelper.h rename to linux/devices/ploc/PlocSupvUartMan.h index d2a3a3ec..6781ec67 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -158,11 +158,12 @@ class PlocSupvHelper : public DeviceCommunicationIF, static uint32_t buildProgParams1(uint8_t percent, uint16_t seqCount); private: - static constexpr ReturnValue_t NO_PACKET_FOUND = returnvalue::makeCode(1, 0); - static constexpr ReturnValue_t DECODE_BUF_TOO_SMALL = returnvalue::makeCode(1, 1); + 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, 2); - static constexpr ReturnValue_t POSSIBLE_PACKET_LOSS_CONSECUTIVE_END = returnvalue::makeCode(1, 3); + returnvalue::makeCode(1, 3); + static constexpr ReturnValue_t POSSIBLE_PACKET_LOSS_CONSECUTIVE_END = returnvalue::makeCode(1, 4); static const uint16_t CRC16_INIT = 0xFFFF; // Event buffer reply will carry 24 space packets with 1016 bytes and one space packet with @@ -211,17 +212,17 @@ class PlocSupvHelper : public DeviceCommunicationIF, EventBufferRequest eventBufferReq; - enum class InternalState { IDLE, RUNNING, FINISH }; + enum class InternalState { SLEEPING, DEFAULT, LONGER_REQUEST, GO_TO_SLEEP }; enum class Request { - HANDLER_DRIVEN, + DEFAULT, UPDATE, CONTINUE_UPDATE, REQUEST_EVENT_BUFFER, CHECK_MEMORY, }; - InternalState state = InternalState::IDLE; - Request request = Request::HANDLER_DRIVEN; + InternalState state = InternalState::SLEEPING; + Request request = Request::DEFAULT; #ifdef XIPHOS_Q7S SdCardManager* sdcMan = nullptr; @@ -255,7 +256,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, // Remembers APID to know at which command a procedure failed uint16_t rememberApid = 0; - bool handleRunningRequest(); + ReturnValue_t handleRunningLongerRequest(); bool handleUartReception(); ReturnValue_t encodeAndSendPacket(const uint8_t* sendData, size_t sendLen); @@ -367,6 +368,8 @@ class PlocSupvHelper : public DeviceCommunicationIF, */ ReturnValue_t requestReceiveMessage(CookieIF* cookie, size_t requestLen) override; ReturnValue_t readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) override; + + void performUartShutdown(); }; #endif /* BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_ */ From 23025eec7a692dbd4a04d878c64f3196c1d81a9e Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 7 Nov 2022 10:30:09 +0100 Subject: [PATCH 028/176] no payload packet impl --- .../devicedefinitions/PlocMPSoCDefinitions.h | 34 +-- .../PlocSupervisorDefinitions.h | 194 ++++++++++-------- linux/devices/ploc/PlocSupervisorHandler.cpp | 10 +- mission/devices/devicedefinitions/SpBase.h | 10 +- 4 files changed, 137 insertions(+), 111 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index a373d96b..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.setFullPacketLen(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.setFullPacketLen(COMMAND_LENGTH + CRC_SIZE); + 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.setFullPacketLen(MIN_FIXED_PAYLOAD_LENGTH + memLen * 4 + CRC_SIZE); + 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.setFullPacketLen(nameSize + sizeof(NULL_TERMINATOR) + sizeof(accessMode) + CRC_SIZE); + 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.setFullPacketLen(nameSize + sizeof(NULL_TERMINATOR) + CRC_SIZE); + 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.setFullPacketLen(static_cast(writeLen) + 4 + CRC_SIZE); + 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.setFullPacketLen(nameSize + sizeof(NULL_TERMINATOR) + CRC_SIZE); + 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.setFullPacketLen(commandDataLen + CRC_SIZE); + 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.setFullPacketLen(commandDataLen + sizeof(MAX_AMPLITUDE) + CRC_SIZE); + 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.setFullPacketLen(commandDataLen + sizeof(NULL_TERMINATOR) + CRC_SIZE); + spParams.setFullPayloadLen(commandDataLen + sizeof(NULL_TERMINATOR) + CRC_SIZE); result = lengthCheck(commandDataLen); if (result != returnvalue::OK) { return result; @@ -657,8 +657,8 @@ class TcCamcmdSend : public TcBase { return INVALID_LENGTH; } uint16_t dataLen = static_cast(commandDataLen + sizeof(CARRIAGE_RETURN)); - spParams.setFullPacketLen(sizeof(dataLen) + commandDataLen + sizeof(CARRIAGE_RETURN) + - CRC_SIZE); + 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 75bbdb28..cdc5f24a 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -13,6 +13,8 @@ #include "linux/devices/devicedefinitions/SupvReturnValuesIF.h" #include "mission/devices/devicedefinitions/SpBase.h" +using namespace returnvalue; + namespace supv { typedef struct { @@ -218,14 +220,28 @@ static const uint16_t APID_GET_HK_REPORT = 0xC6; static const uint16_t APID_MASK = 0x3FF; 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 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; -/** - * 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 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 + +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; @@ -233,6 +249,10 @@ 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 constexpr size_t MIN_PAYLOAD_LEN = SECONDARY_HEADER_LEN + CRC_LEN; +static constexpr size_t MIN_TC_LEN = ccsds::HEADER_LEN + MIN_PAYLOAD_LEN; +static constexpr size_t PAYLOAD_OFFSET = ccsds::HEADER_LEN + SECONDARY_HEADER_LEN; + struct UpdateParams { std::string file; uint8_t memId; @@ -335,29 +355,6 @@ 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 - -static constexpr size_t TIMESTAMP_LEN = 7; -static constexpr size_t SECONDARY_HEADER_LEN = TIMESTAMP_LEN + 1; -static constexpr size_t CRC_LEN = 2; - struct SupvTcParams : public ploc::SpTcParams { public: SupvTcParams(SpacePacketCreator& creator) : ploc::SpTcParams(creator) {} @@ -366,20 +363,49 @@ struct SupvTcParams : public ploc::SpTcParams { : ploc::SpTcParams(creator, buf, maxSize) {} void setLenFromPayloadLen(size_t payloadLen) { - setFullPacketLen(ccsds::HEADER_LEN + SECONDARY_HEADER_LEN + payloadLen + CRC_LEN); + setFullPayloadLen(ccsds::HEADER_LEN + SECONDARY_HEADER_LEN + payloadLen + CRC_LEN); } }; class SupvTcBase : public ploc::SpTcBase { public: - SupvTcBase(SupvTcParams params) : ploc::SpTcBase(params) {} + SupvTcBase(SupvTcParams params) : ploc::SpTcBase(params) { setup(); } - SupvTcBase(SupvTcParams params, uint16_t apid, uint16_t seqCount) - : ploc::SpTcBase(params, apid, seqCount) {} + SupvTcBase(SupvTcParams params, uint16_t apid, uint8_t serviceId, uint16_t seqCount) + : ploc::SpTcBase(params, apid, seqCount), serviceId(serviceId) { + if (setup() == OK) { + params.buf + supv::PAYLOAD_OFFSET = serviceId; + } + } + + private: + uint8_t serviceId = 0; + + ReturnValue_t setup() { + 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); + return returnvalue::OK; + } +}; + +class NoPayloadPacket : public SupvTcBase { + public: + NoPayloadPacket(SupvTcParams params, uint16_t apid, uint8_t serviceId, uint16_t seqCount) + : SupvTcBase(params, apid, serviceId, seqCount) {} + + ReturnValue_t buildPacket() { + ReturnValue_t result = checkSizeAndSerializeHeader(); + if (result != OK) { + return result; + } + return calcAndSetCrc(); + } private: }; - /** * @brief This class creates a space packet containing only the header data and the CRC. */ @@ -393,7 +419,7 @@ class ApidOnlyPacket : public ploc::SpTcBase { * @note Sequence count of empty packet is always 1. */ ApidOnlyPacket(ploc::SpTcParams params, uint16_t apid) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(LENGTH_EMPTY_TC); + spParams.setFullPayloadLen(MIN_TC_LEN); spParams.creator.setApid(apid); } @@ -402,7 +428,7 @@ class ApidOnlyPacket : public ploc::SpTcBase { if (res != returnvalue::OK) { return res; } - return calcCrc(); + return calcAndSetCrc(); } private: @@ -428,7 +454,7 @@ class MPSoCBootSelect : public ploc::SpTcBase { * @note Selection of partitions is currently not supported. */ MPSoCBootSelect(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SEL_MPSOC_BOOT_IMAGE); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -439,7 +465,7 @@ class MPSoCBootSelect : public ploc::SpTcBase { return res; } initPacket(mem, bp0, bp1, bp2); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -474,7 +500,7 @@ class EnableNvms : public ploc::SpTcBase { * @param bp2 Partition pin 2 */ EnableNvms(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_ENABLE_NVMS); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -485,7 +511,7 @@ class EnableNvms : public ploc::SpTcBase { return res; } initPacket(nvm01, nvm3); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -504,7 +530,7 @@ class EnableNvms : public ploc::SpTcBase { class SetTimeRef : public ploc::SpTcBase { public: SetTimeRef(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_TIME_REF); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -518,7 +544,7 @@ class SetTimeRef : public ploc::SpTcBase { if (res != returnvalue::OK) { return res; } - return calcCrc(); + return calcAndSetCrc(); } private: @@ -583,7 +609,7 @@ class SetBootTimeout : public ploc::SpTcBase { * @param timeout The boot timeout in milliseconds. */ SetBootTimeout(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_BOOT_TIMEOUT); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -594,7 +620,7 @@ class SetBootTimeout : public ploc::SpTcBase { return res; } initPacket(timeout); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -620,7 +646,7 @@ class SetRestartTries : public ploc::SpTcBase { * @param restartTries Maximum restart tries to set. */ SetRestartTries(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_MAX_RESTART_TRIES); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -631,7 +657,7 @@ class SetRestartTries : public ploc::SpTcBase { return res; } initPacket(restartTries); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -654,7 +680,7 @@ class DisablePeriodicHkTransmission : public ploc::SpTcBase { * @brief Constructor */ DisablePeriodicHkTransmission(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_DISABLE_HK); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -665,7 +691,7 @@ class DisablePeriodicHkTransmission : public ploc::SpTcBase { return res; } initPacket(); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -690,7 +716,7 @@ class LatchupAlert : public ploc::SpTcBase { * 3 - 3.3V, 4 - NVM_4XO, 5 - MISSION, 6 - SAFECOTS) */ LatchupAlert(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -705,7 +731,7 @@ class LatchupAlert : public ploc::SpTcBase { return res; } initPacket(latchupId); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -728,7 +754,7 @@ class SetAlertlimit : public ploc::SpTcBase { * @param dutycycle */ SetAlertlimit(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ALERT_LIMIT); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -742,7 +768,7 @@ class SetAlertlimit : public ploc::SpTcBase { if (res != returnvalue::OK) { return res; } - return calcCrc(); + return calcAndSetCrc(); } private: @@ -771,7 +797,7 @@ class SetAdcEnabledChannels : public ploc::SpTcBase { * @param ch Defines channels to be enabled or disabled. */ SetAdcEnabledChannels(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ADC_ENABLED_CHANNELS); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -782,7 +808,7 @@ class SetAdcEnabledChannels : public ploc::SpTcBase { return res; } initPacket(ch); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -810,7 +836,7 @@ class SetAdcWindowAndStride : public ploc::SpTcBase { * @param stridingStepSize */ SetAdcWindowAndStride(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ADC_WINDOW_AND_STRIDE); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -821,7 +847,7 @@ class SetAdcWindowAndStride : public ploc::SpTcBase { return res; } initPacket(windowSize, stridingStepSize); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -850,7 +876,7 @@ class SetAdcThreshold : public ploc::SpTcBase { * @param threshold */ SetAdcThreshold(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ADC_THRESHOLD); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -861,7 +887,7 @@ class SetAdcThreshold : public ploc::SpTcBase { return res; } initPacket(threshold); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -888,7 +914,7 @@ class RunAutoEmTests : public ploc::SpTcBase { * @param test 1 - complete EM test, 2 - Short test (only memory readback NVM0,1,3) */ RunAutoEmTests(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_RUN_AUTO_EM_TESTS); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -899,7 +925,7 @@ class RunAutoEmTests : public ploc::SpTcBase { return res; } initPacket(test); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -930,7 +956,7 @@ class MramCmd : public ploc::SpTcBase { * @note The content at the stop address is excluded from the dump or wipe operation. */ MramCmd(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -947,7 +973,7 @@ class MramCmd : public ploc::SpTcBase { return res; } initPacket(start, stop); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -984,7 +1010,7 @@ class SetGpio : public ploc::SpTcBase { * @param val */ SetGpio(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_GPIO); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -995,7 +1021,7 @@ class SetGpio : public ploc::SpTcBase { return res; } initPacket(port, pin, val); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -1028,7 +1054,7 @@ class ReadGpio : public ploc::SpTcBase { * @param pin */ ReadGpio(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(DATA_FIELD_LENGTH); + spParams.setFullPayloadLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_READ_GPIO); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1039,7 +1065,7 @@ class ReadGpio : public ploc::SpTcBase { return res; } initPacket(port, pin); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -1085,7 +1111,7 @@ class FactoryReset : public ploc::SpTcBase { return res; } initPacket(op); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -1105,14 +1131,14 @@ class FactoryReset : public ploc::SpTcBase { default: break; } - spParams.setFullPacketLen(packetDataLen); + spParams.setFullPayloadLen(packetDataLen); } }; class SetShutdownTimeout : public ploc::SpTcBase { public: SetShutdownTimeout(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(PAYLOAD_LEN + 2); + spParams.setFullPayloadLen(PAYLOAD_LEN + 2); spParams.creator.setApid(APID_SET_SHUTDOWN_TIMEOUT); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1123,7 +1149,7 @@ class SetShutdownTimeout : public ploc::SpTcBase { return res; } initPacket(timeout); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -1151,7 +1177,7 @@ class CheckMemory : public ploc::SpTcBase { * @param length Length in bytes of memory region */ CheckMemory(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(PAYLOAD_LENGTH + 2); + spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); spParams.creator.setApid(APID_CHECK_MEMORY); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1162,7 +1188,7 @@ class CheckMemory : public ploc::SpTcBase { return res; } initPacket(memoryId, startAddress, length); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -1216,7 +1242,7 @@ class WriteMemory : public ploc::SpTcBase { if (res != returnvalue::OK) { return res; } - return calcCrc(); + 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. @@ -1230,9 +1256,9 @@ class WriteMemory : public ploc::SpTcBase { uint8_t* updateData) { uint8_t* data = payloadStart; if (updateDataLen % 2 != 0) { - spParams.setFullPacketLen(META_DATA_LENGTH + updateDataLen + 1 + 2); + spParams.setFullPayloadLen(META_DATA_LENGTH + updateDataLen + 1 + 2); } else { - spParams.setFullPacketLen(META_DATA_LENGTH + updateDataLen + 2); + spParams.setFullPayloadLen(META_DATA_LENGTH + updateDataLen + 2); } // To avoid crashes in this unexpected case ReturnValue_t result = checkPayloadLen(); @@ -1264,7 +1290,7 @@ class WriteMemory : public ploc::SpTcBase { class EraseMemory : public ploc::SpTcBase { public: EraseMemory(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(PAYLOAD_LENGTH + 2); + spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); spParams.creator.setApid(APID_ERASE_MEMORY); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1275,7 +1301,7 @@ class EraseMemory : public ploc::SpTcBase { return res; } initPacket(memoryId, startAddress, length); - return calcCrc(); + return calcAndSetCrc(); } private: @@ -1306,7 +1332,7 @@ class EraseMemory : public ploc::SpTcBase { class EnableAutoTm : public ploc::SpTcBase { public: EnableAutoTm(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(PAYLOAD_LENGTH + 2); + spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); spParams.creator.setApid(APID_AUTO_TM); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1317,7 +1343,7 @@ class EnableAutoTm : public ploc::SpTcBase { return res; } payloadStart[0] = ENABLE; - return calcCrc(); + return calcAndSetCrc(); } private: @@ -1331,7 +1357,7 @@ class EnableAutoTm : public ploc::SpTcBase { class DisableAutoTm : public ploc::SpTcBase { public: DisableAutoTm(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(PAYLOAD_LENGTH + 2); + spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); spParams.creator.setApid(APID_AUTO_TM); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1342,7 +1368,7 @@ class DisableAutoTm : public ploc::SpTcBase { return res; } payloadStart[0] = DISABLE; - return calcCrc(); + return calcAndSetCrc(); } private: @@ -1366,7 +1392,7 @@ class RequestLoggingData : public ploc::SpTcBase { }; RequestLoggingData(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPacketLen(PAYLOAD_LENGTH + 2); + spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); spParams.creator.setApid(APID_REQUEST_LOGGING_DATA); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1383,7 +1409,7 @@ class RequestLoggingData : public ploc::SpTcBase { } payloadStart[0] = static_cast(sa); payloadStart[1] = tpc; - return calcCrc(); + return calcAndSetCrc(); } private: diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 95f64510..c2797494 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -1028,7 +1028,7 @@ ReturnValue_t PlocSupervisorHandler::handleHkReport(const uint8_t* data) { 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; @@ -1106,7 +1106,7 @@ ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data) return result; } - uint16_t offset = supv::DATA_FIELD_OFFSET; + uint16_t offset = supv::PAYLOAD_OFFSET; bootStatusReport.socState = *(data + offset); offset += 1; bootStatusReport.powerCycles = *(data + offset); @@ -1171,7 +1171,7 @@ ReturnValue_t PlocSupervisorHandler::handleLatchupStatusReport(const uint8_t* da return result; } - uint16_t offset = supv::DATA_FIELD_OFFSET; + uint16_t offset = supv::PAYLOAD_OFFSET; latchupStatusReport.id = *(data + offset); offset += 1; latchupStatusReport.cnt0 = *(data + offset) << 8 | *(data + offset + 1); @@ -1255,7 +1255,7 @@ ReturnValue_t PlocSupervisorHandler::handleLoggingReport(const uint8_t* data) { return result; } - const uint8_t* dataField = data + supv::DATA_FIELD_OFFSET + sizeof(supv::RequestLoggingData::Sa); + const uint8_t* dataField = data + supv::PAYLOAD_OFFSET + sizeof(supv::RequestLoggingData::Sa); result = loggingReport.read(); if (result != returnvalue::OK) { return result; @@ -1291,7 +1291,7 @@ ReturnValue_t PlocSupervisorHandler::handleAdcReport(const uint8_t* data) { 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; diff --git a/mission/devices/devicedefinitions/SpBase.h b/mission/devices/devicedefinitions/SpBase.h index edc91334..8a5dd079 100644 --- a/mission/devices/devicedefinitions/SpBase.h +++ b/mission/devices/devicedefinitions/SpBase.h @@ -14,12 +14,12 @@ struct SpTcParams { SpTcParams(SpacePacketCreator& creator, uint8_t* buf, size_t maxSize) : creator(creator), buf(buf), maxSize(maxSize) {} - void setFullPacketLen(size_t fullPacketLen_) { fullPacketLen = fullPacketLen_; } + void setFullPayloadLen(size_t fullPayloadLen_) { fullPayloadLen = fullPayloadLen_; } SpacePacketCreator& creator; uint8_t* buf = nullptr; size_t maxSize = 0; - size_t fullPacketLen = 0; + size_t fullPayloadLen = 0; }; class SpTcBase { @@ -37,7 +37,7 @@ class SpTcBase { } void updateSpFields() { - spParams.creator.setDataLenField(spParams.fullPacketLen - 1); + spParams.creator.setDataLenField(spParams.fullPayloadLen - 1); spParams.creator.setPacketType(ccsds::PacketType::TC); } @@ -48,7 +48,7 @@ class SpTcBase { uint16_t getApid() const { return spParams.creator.getApid(); } ReturnValue_t checkPayloadLen() { - if (ccsds::HEADER_LEN + spParams.fullPacketLen > spParams.maxSize) { + if (ccsds::HEADER_LEN + spParams.fullPayloadLen > spParams.maxSize) { return SerializeIF::BUFFER_TOO_SHORT; } @@ -69,7 +69,7 @@ class SpTcBase { return serializeHeader(); } - ReturnValue_t calcCrc() { + ReturnValue_t calcAndSetCrc() { /* Calculate crc */ uint16_t crc = CRC::crc16ccitt(spParams.buf, getFullPacketLen() - 2); From 95a3ea1d23f586d7a416f1ce56e29e662a818c18 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 7 Nov 2022 11:19:10 +0100 Subject: [PATCH 029/176] start using new packet format --- .../PlocSupervisorDefinitions.h | 51 ++++----------- linux/devices/ploc/PlocSupervisorHandler.cpp | 64 ++++++++++--------- linux/devices/ploc/PlocSupervisorHandler.h | 4 +- linux/devices/ploc/PlocSupvUartMan.cpp | 4 +- linux/devices/ploc/PlocSupvUartMan.h | 2 +- 5 files changed, 53 insertions(+), 72 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index cdc5f24a..257a8c53 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -355,11 +355,11 @@ enum PoolIds : lp_id_t { ADC_ENG_15 }; -struct SupvTcParams : public ploc::SpTcParams { +struct TcParams : public ploc::SpTcParams { public: - SupvTcParams(SpacePacketCreator& creator) : ploc::SpTcParams(creator) {} + TcParams(SpacePacketCreator& creator) : ploc::SpTcParams(creator) {} - SupvTcParams(SpacePacketCreator& creator, uint8_t* buf, size_t maxSize) + TcParams(SpacePacketCreator& creator, uint8_t* buf, size_t maxSize) : ploc::SpTcParams(creator, buf, maxSize) {} void setLenFromPayloadLen(size_t payloadLen) { @@ -367,14 +367,14 @@ struct SupvTcParams : public ploc::SpTcParams { } }; -class SupvTcBase : public ploc::SpTcBase { +class TcBase : public ploc::SpTcBase { public: - SupvTcBase(SupvTcParams params) : ploc::SpTcBase(params) { setup(); } + TcBase(TcParams params) : ploc::SpTcBase(params) { setup(); } - SupvTcBase(SupvTcParams params, uint16_t apid, uint8_t serviceId, uint16_t seqCount) + TcBase(TcParams params, uint16_t apid, uint8_t serviceId, uint16_t seqCount) : ploc::SpTcBase(params, apid, seqCount), serviceId(serviceId) { - if (setup() == OK) { - params.buf + supv::PAYLOAD_OFFSET = serviceId; + if (setup() == OK and params.buf != nullptr) { + params.buf[supv::PAYLOAD_OFFSET] = serviceId; } } @@ -391,11 +391,13 @@ class SupvTcBase : public ploc::SpTcBase { } }; -class NoPayloadPacket : public SupvTcBase { +class NoPayloadPacket : public TcBase { public: - NoPayloadPacket(SupvTcParams params, uint16_t apid, uint8_t serviceId, uint16_t seqCount) - : SupvTcBase(params, apid, serviceId, seqCount) {} + 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, seqId) {} ReturnValue_t buildPacket() { ReturnValue_t result = checkSizeAndSerializeHeader(); if (result != OK) { @@ -406,33 +408,6 @@ class NoPayloadPacket : public SupvTcBase { private: }; -/** - * @brief This class creates a space packet containing only the header data and the CRC. - */ -class ApidOnlyPacket : public ploc::SpTcBase { - 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.setFullPayloadLen(MIN_TC_LEN); - spParams.creator.setApid(apid); - } - - ReturnValue_t buildPacket() { - auto res = checkSizeAndSerializeHeader(); - if (res != returnvalue::OK) { - return res; - } - return calcAndSetCrc(); - } - - private: -}; /** * @brief This class can be used to generate the space packet selecting the boot image of diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index c2797494..853741cf 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -221,17 +221,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(HkServiceIds::GET_REPORT)); result = returnvalue::OK; break; } case START_MPSOC: { - prepareEmptyCmd(APID_START_MPSOC); + prepareEmptyCmd(APID_BOOT_MAN, static_cast(BootManServiceIds::START_MPSOC)); result = returnvalue::OK; break; } case SHUTDOWN_MPSOC: { - prepareEmptyCmd(APID_SHUTWOWN_MPSOC); + prepareEmptyCmd(APID_BOOT_MAN, static_cast(BootManServiceIds::SHUTDOWN_MPSOC)); result = returnvalue::OK; break; } @@ -241,7 +241,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case RESET_MPSOC: { - prepareEmptyCmd(APID_RESET_MPSOC); + prepareEmptyCmd(APID_BOOT_MAN, static_cast(BootManServiceIds::RESET_MPSOC)); result = returnvalue::OK; break; } @@ -265,7 +265,8 @@ 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(BootManServiceIds::GET_BOOT_STATUS_REPORT)); result = returnvalue::OK; break; } @@ -297,20 +298,22 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d 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); + prepareEmptyCmd(APID_LATCHUP_MON, + static_cast(LatchupMonServiceIds::GET_STATUS_REPORT)); result = returnvalue::OK; 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 RUN_AUTO_EM_TESTS: { result = prepareRunAutoEmTest(commandData); break; @@ -333,11 +336,11 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d result = returnvalue::OK; break; } - case RESTART_SUPERVISOR: { - prepareEmptyCmd(APID_RESTART_SUPERVISOR); - 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); @@ -365,18 +368,19 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d finishTcPrep(packet.getFullPacketLen()); break; } - case START_MPSOC_QUIET: { - prepareEmptyCmd(APID_START_MPSOC_QUIET); - result = returnvalue::OK; - break; - } + // Removed command + // 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); + prepareEmptyCmd(APID_BOOT_MAN, static_cast(BootManServiceIds::FACTORY_FLASH)); result = returnvalue::OK; break; } @@ -430,7 +434,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case RESET_PL: { - prepareEmptyCmd(APID_RESET_PL); + prepareEmptyCmd(APID_BOOT_MAN, static_cast(BootManServiceIds::RESET_PL)); result = returnvalue::OK; break; } @@ -1414,8 +1418,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; diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index d9776c36..d731a314 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -102,7 +102,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 @@ -236,7 +236,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { * @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. diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 5bab8d13..ce197cf4 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -24,6 +24,7 @@ #include "mission/utility/Timestamp.h" using namespace returnvalue; +using namespace supv; PlocSupvHelper::PlocSupvHelper(object_id_t objectId) : SystemObject(objectId), @@ -498,7 +499,8 @@ ReturnValue_t PlocSupvHelper::selectMemory() { ReturnValue_t PlocSupvHelper::prepareUpdate() { ReturnValue_t result = returnvalue::OK; resetSpParams(); - supv::ApidOnlyPacket packet(spParams, supv::APID_PREPARE_UPDATE); + supv::NoPayloadPacket packet(spParams, supv::APID_BOOT_MAN, + static_cast(BootManServiceIds::PREPARE_UPDATE)); result = packet.buildPacket(); if (result != returnvalue::OK) { return result; diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index 6781ec67..c0f23f22 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -238,7 +238,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]{}; SpacePacketCreator creator; - ploc::SpTcParams spParams = ploc::SpTcParams(creator); + supv::TcParams spParams = supv::TcParams(creator); std::array tmBuf{}; From f32f68d0e00fd1c789e7ca9d9bfb3417a9d4bb2c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 7 Nov 2022 11:26:36 +0100 Subject: [PATCH 030/176] continue switch to new packet format --- .../PlocSupervisorDefinitions.h | 16 +++++++++------- linux/devices/ploc/PlocSupervisorHandler.cpp | 2 +- 2 files changed, 10 insertions(+), 8 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 257a8c53..e0c4f960 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -378,6 +378,10 @@ class TcBase : public ploc::SpTcBase { } } + void setLenFromPayloadLen(size_t payloadLen) { + spParams.setFullPayloadLen(ccsds::HEADER_LEN + SECONDARY_HEADER_LEN + payloadLen + CRC_LEN); + } + private: uint8_t serviceId = 0; @@ -387,6 +391,7 @@ class TcBase : public ploc::SpTcBase { return returnvalue::FAILED; } std::memset(spParams.buf + ccsds::HEADER_LEN, 0, TIMESTAMP_LEN); + payloadStart = spParams.buf + SECONDARY_HEADER_LEN; return returnvalue::OK; } }; @@ -413,7 +418,7 @@ class NoPayloadPacket : public TcBase { * @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; @@ -428,8 +433,8 @@ class MPSoCBootSelect : public ploc::SpTcBase { * * @note Selection of partitions is currently not supported. */ - MPSoCBootSelect(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPayloadLen(DATA_FIELD_LENGTH); + MPSoCBootSelect(TcParams params) : TcBase(params) { + params.setLenFromPayloadLen(4); spParams.creator.setApid(APID_SEL_MPSOC_BOOT_IMAGE); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -444,16 +449,13 @@ class MPSoCBootSelect : public ploc::SpTcBase { } 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)); + payloadStart[0] = 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)); diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 853741cf..65eda209 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -1431,7 +1431,7 @@ ReturnValue_t PlocSupervisorHandler::prepareEmptyCmd(uint16_t apid, uint8_t serv 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; } From e46bb42266c4d9d282c58cea774a6ea7d8ba4f4a Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 7 Nov 2022 13:37:51 +0100 Subject: [PATCH 031/176] continue switch to new packet format --- .../PlocSupervisorDefinitions.h | 332 +++++++----------- linux/devices/ploc/PlocSupervisorHandler.cpp | 48 +-- linux/devices/ploc/PlocSupervisorHandler.h | 2 +- linux/devices/ploc/PlocSupvUartMan.cpp | 2 +- mission/devices/devicedefinitions/SpBase.h | 15 +- 5 files changed, 171 insertions(+), 228 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index e0c4f960..e34f6ab0 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -33,6 +33,8 @@ typedef struct { uint8_t tm_year; // years since 1900 } tas_time_t; +static constexpr uint16_t DEFAULT_SEQ_COUNT = 0; + /** Command IDs */ static const DeviceCommandId_t NONE = 0; static const DeviceCommandId_t GET_HK_REPORT = 1; @@ -122,14 +124,16 @@ static const uint16_t APID_DATA_LOGGER_DATA = 0x20D; // 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 constexpr uint16_t APID_TMTC_MAN = 0x00; -static constexpr uint16_t APID_HK = 0x01; -static constexpr uint16_t APID_BOOT_MAN = 0x02; -static constexpr uint16_t APID_LATCHUP_MON = 0x03; -static constexpr uint16_t APID_ADC_MON = 0x04; -static constexpr uint16_t APID_MEM_MAN = 0x05; -static constexpr uint16_t APID_DATA_LOGGER = 0x06; -static constexpr uint16_t APID_WDOG_MAN = 0x07; +enum Apids { + TMTC_MAN = 0x00, + HK = 0x01, + BOOT_MAN = 0x02, + LATCHUP_MON = 0x03, + ADC_MON = 0x04, + MEM_MAN = 0x05, + DATA_LOGGER = 0x06, + WDOG_MAN = 0x07 +}; enum class HkServiceIds : uint8_t { ENABLE = 0x01, @@ -170,7 +174,13 @@ enum class LatchupMonServiceIds : uint8_t { // Right now, none of the commands seem to be implemented, but still // keep the enum here in case some are added -enum class AdcMonServiceIds : uint8_t {}; +enum class AdcMonServiceIds : 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 DataLoggerServiceIds : uint8_t { FACTORY_RESET = 0x07 }; @@ -178,49 +188,9 @@ enum class DataLoggerServiceIds : uint8_t { FACTORY_RESET = 0x07 }; // keep the enum here in case some are added enum class WdogManServiceIds : uint8_t {}; -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; - -static const uint16_t APID_GET_HK_REPORT = 0xC6; - static const uint16_t APID_MASK = 0x3FF; static const uint16_t SEQUENCE_COUNT_MASK = 0xFFF; -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; @@ -369,29 +339,43 @@ struct TcParams : public ploc::SpTcParams { class TcBase : public ploc::SpTcBase { public: - TcBase(TcParams params) : ploc::SpTcBase(params) { setup(); } + TcBase(TcParams params) : TcBase(params, 0x00, 0x00, MIN_PAYLOAD_LEN) {} - TcBase(TcParams params, uint16_t apid, uint8_t serviceId, uint16_t seqCount) - : ploc::SpTcBase(params, apid, seqCount), serviceId(serviceId) { - if (setup() == OK and params.buf != nullptr) { - params.buf[supv::PAYLOAD_OFFSET] = serviceId; + 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, fullSpDataLenFromPayloadLen(payloadLen), seqCount) { + setup(serviceId); + } + + void setServiceId(uint8_t id) { + if (spParams.maxSize < MIN_PAYLOAD_LEN) { + return; } + payloadStart[supv::PAYLOAD_OFFSET] = id; + } + + static size_t fullSpDataLenFromPayloadLen(size_t payloadLen) { + return SECONDARY_HEADER_LEN + payloadLen + CRC_LEN; } void setLenFromPayloadLen(size_t payloadLen) { - spParams.setFullPayloadLen(ccsds::HEADER_LEN + SECONDARY_HEADER_LEN + payloadLen + CRC_LEN); + spParams.setFullPayloadLen(fullSpDataLenFromPayloadLen(payloadLen)); + updateLenFromParams(); } private: - uint8_t serviceId = 0; - - ReturnValue_t setup() { + 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 + SECONDARY_HEADER_LEN; + payloadStart = spParams.buf + ccsds::HEADER_LEN + SECONDARY_HEADER_LEN; + payloadStart[supv::PAYLOAD_OFFSET] = serviceId; return returnvalue::OK; } }; @@ -402,7 +386,8 @@ class NoPayloadPacket : public TcBase { : NoPayloadPacket(params, apid, serviceId, 0) {} NoPayloadPacket(TcParams params, uint16_t apid, uint8_t serviceId, uint16_t seqId) - : TcBase(params, apid, serviceId, seqId) {} + : TcBase(params, apid, serviceId, MIN_PAYLOAD_LEN, seqId) {} + ReturnValue_t buildPacket() { ReturnValue_t result = checkSizeAndSerializeHeader(); if (result != OK) { @@ -433,11 +418,8 @@ class MPSoCBootSelect : public TcBase { * * @note Selection of partitions is currently not supported. */ - MPSoCBootSelect(TcParams params) : TcBase(params) { - params.setLenFromPayloadLen(4); - spParams.creator.setApid(APID_SEL_MPSOC_BOOT_IMAGE); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + MPSoCBootSelect(TcParams params) + : TcBase(params, Apids::BOOT_MAN, static_cast(BootManServiceIds::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(); @@ -449,16 +431,11 @@ class MPSoCBootSelect : public TcBase { } private: - 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; - void initPacket(uint8_t mem = 0, uint8_t bp0 = 0, uint8_t bp1 = 0, uint8_t bp2 = 0) { payloadStart[0] = 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)); + payloadStart[1] = bp0; + payloadStart[2] = bp1; + payloadStart[3] = bp2; } }; @@ -466,51 +443,49 @@ class MPSoCBootSelect : public TcBase { * @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.setFullPayloadLen(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 calcAndSetCrc(); - } - - 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; - } -}; +// 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.setFullPayloadLen(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 calcAndSetCrc(); +// } +// +// 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; +// } +// }; /** * @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.setFullPayloadLen(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, Apids::TMTC_MAN, static_cast(TmtcServiceIds::TIME_REF), 8) {} ReturnValue_t buildPacket(Clock::TimeOfDay_t* time) { auto res = checkSizeAndSerializeHeader(); @@ -525,8 +500,6 @@ class SetTimeRef : public ploc::SpTcBase { } 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) { @@ -578,18 +551,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.setFullPayloadLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_BOOT_TIMEOUT); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetBootTimeout(TcParams params) + : TcBase(params, Apids::BOOT_MAN, static_cast(BootManServiceIds::SET_BOOT_TIMEOUT), + PAYLOAD_LEN) {} ReturnValue_t buildPacket(uint32_t timeout) { auto res = checkSizeAndSerializeHeader(); @@ -601,9 +573,6 @@ class SetBootTimeout : public ploc::SpTcBase { } 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; @@ -615,18 +584,16 @@ class SetBootTimeout : public ploc::SpTcBase { /** * @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.setFullPayloadLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_MAX_RESTART_TRIES); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetRestartTries(TcParams params) + : TcBase(params, Apids::BOOT_MAN, + static_cast(BootManServiceIds::SET_MAX_REBOOT_TRIES), 1) {} ReturnValue_t buildPacket(uint8_t restartTries) { auto res = checkSizeAndSerializeHeader(); @@ -640,9 +607,6 @@ class SetRestartTries : public ploc::SpTcBase { 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; } }; @@ -651,16 +615,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.setFullPayloadLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_DISABLE_HK); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + DisablePeriodicHkTransmission(TcParams params) + : TcBase(params, Apids::HK, static_cast(HkServiceIds::ENABLE), 1) {} ReturnValue_t buildPacket() { auto res = checkSizeAndSerializeHeader(); @@ -672,9 +633,6 @@ class DisablePeriodicHkTransmission : public ploc::SpTcBase { } private: - /** Restart tries value (uint8_t) and crc (uint16_t) */ - static const uint16_t DATA_FIELD_LENGTH = 3; - void initPacket() { payloadStart[0] = false; } }; @@ -683,7 +641,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 @@ -692,16 +650,13 @@ 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.setFullPayloadLen(DATA_FIELD_LENGTH); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + LatchupAlert(TcParams params) : TcBase(params, Apids::LATCHUP_MON) { setLenFromPayloadLen(1); } ReturnValue_t buildPacket(bool state, uint8_t latchupId) { if (state) { - spParams.creator.setApid(APID_ENABLE_LATCHUP_ALERT); + setServiceId(static_cast(LatchupMonServiceIds::ENABLE)); } else { - spParams.creator.setApid(APID_DISABLE_LATCHUP_ALERT); + setServiceId(static_cast(LatchupMonServiceIds::DISABLE)); } auto res = checkSizeAndSerializeHeader(); if (res != returnvalue::OK) { @@ -712,16 +667,12 @@ class LatchupAlert : public ploc::SpTcBase { } 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 @@ -730,11 +681,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.setFullPayloadLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_ALERT_LIMIT); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetAlertlimit(TcParams params) + : TcBase(params, Apids::LATCHUP_MON, + static_cast(LatchupMonServiceIds::SET_ALERT_LIMIT), 5) {} ReturnValue_t buildPacket(uint8_t latchupId, uint32_t dutycycle) { auto res = checkSizeAndSerializeHeader(); @@ -749,9 +698,6 @@ class SetAlertlimit : public ploc::SpTcBase { } 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; @@ -766,18 +712,16 @@ class SetAlertlimit : public ploc::SpTcBase { /** * @brief This class packages the space packet to enable or disable ADC channels. */ -class SetAdcEnabledChannels : public ploc::SpTcBase { +class SetAdcEnabledChannels : public TcBase { public: /** * @brief Constructor * * @param ch Defines channels to be enabled or disabled. */ - SetAdcEnabledChannels(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPayloadLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_ADC_ENABLED_CHANNELS); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetAdcEnabledChannels(TcParams params) + : TcBase(params, Apids::ADC_MON, static_cast(AdcMonServiceIds::SET_ENABLED_CHANNELS), + 2) {} ReturnValue_t buildPacket(uint16_t ch) { auto res = checkSizeAndSerializeHeader(); @@ -789,10 +733,6 @@ class SetAdcEnabledChannels : public ploc::SpTcBase { } 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), @@ -814,8 +754,8 @@ class SetAdcWindowAndStride : public ploc::SpTcBase { */ SetAdcWindowAndStride(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setFullPayloadLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_ADC_WINDOW_AND_STRIDE); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + // spParams.creator.setApid(APID_SET_ADC_WINDOW_AND_STRIDE); + // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } ReturnValue_t buildPacket(uint16_t windowSize, uint16_t stridingStepSize) { @@ -854,7 +794,7 @@ class SetAdcThreshold : public ploc::SpTcBase { */ SetAdcThreshold(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setFullPayloadLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_ADC_THRESHOLD); + // spParams.creator.setApid(APID_SET_ADC_THRESHOLD); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -892,7 +832,7 @@ class RunAutoEmTests : public ploc::SpTcBase { */ RunAutoEmTests(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setFullPayloadLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_RUN_AUTO_EM_TESTS); + // spParams.creator.setApid(APID_RUN_AUTO_EM_TESTS); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -934,14 +874,14 @@ class MramCmd : public ploc::SpTcBase { */ MramCmd(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setFullPayloadLen(DATA_FIELD_LENGTH); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } ReturnValue_t buildPacket(uint32_t start, uint32_t stop, MramAction action) { if (action == MramAction::WIPE) { - spParams.creator.setApid(APID_WIPE_MRAM); + // spParams.creator.setApid(APID_WIPE_MRAM); } else if (action == MramAction::DUMP) { - spParams.creator.setApid(APID_DUMP_MRAM); + // spParams.creator.setApid(APID_DUMP_MRAM); } else { sif::debug << "WipeMram: Invalid action specified"; } @@ -988,7 +928,7 @@ class SetGpio : public ploc::SpTcBase { */ SetGpio(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setFullPayloadLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_GPIO); + // spParams.creator.setApid(APID_SET_GPIO); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1032,7 +972,7 @@ class ReadGpio : public ploc::SpTcBase { */ ReadGpio(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setFullPayloadLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_READ_GPIO); + // spParams.creator.setApid(APID_READ_GPIO); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1078,7 +1018,7 @@ class FactoryReset : public ploc::SpTcBase { * @param op */ FactoryReset(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.creator.setApid(APID_FACTORY_RESET); + // spParams.creator.setApid(APID_FACTORY_RESET); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1116,8 +1056,8 @@ class SetShutdownTimeout : public ploc::SpTcBase { public: SetShutdownTimeout(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setFullPayloadLen(PAYLOAD_LEN + 2); - spParams.creator.setApid(APID_SET_SHUTDOWN_TIMEOUT); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + // spParams.creator.setApid(APID_SET_SHUTDOWN_TIMEOUT); + // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } ReturnValue_t buildPacket(uint32_t timeout) { @@ -1155,8 +1095,8 @@ class CheckMemory : public ploc::SpTcBase { */ CheckMemory(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); - spParams.creator.setApid(APID_CHECK_MEMORY); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + // spParams.creator.setApid(APID_CHECK_MEMORY); + // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } ReturnValue_t buildPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { @@ -1202,8 +1142,8 @@ class WriteMemory : public ploc::SpTcBase { * @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); + // spParams.creator.setApid(APID_WRITE_MEMORY); + // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } ReturnValue_t buildPacket(ccsds::SequenceFlags seqFlags, uint16_t sequenceCount, uint8_t memoryId, @@ -1268,8 +1208,8 @@ class EraseMemory : public ploc::SpTcBase { public: EraseMemory(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); - spParams.creator.setApid(APID_ERASE_MEMORY); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + // spParams.creator.setApid(APID_ERASE_MEMORY); + // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } ReturnValue_t buildPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { @@ -1310,8 +1250,8 @@ class EnableAutoTm : public ploc::SpTcBase { public: EnableAutoTm(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); - spParams.creator.setApid(APID_AUTO_TM); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + // spParams.creator.setApid(APID_AUTO_TM); + // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } ReturnValue_t buildPacket() { @@ -1335,8 +1275,8 @@ class DisableAutoTm : public ploc::SpTcBase { public: DisableAutoTm(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); - spParams.creator.setApid(APID_AUTO_TM); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + // spParams.creator.setApid(APID_AUTO_TM); + // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } ReturnValue_t buildPacket() { @@ -1370,8 +1310,8 @@ class RequestLoggingData : public ploc::SpTcBase { RequestLoggingData(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); - spParams.creator.setApid(APID_REQUEST_LOGGING_DATA); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + // spParams.creator.setApid(APID_REQUEST_LOGGING_DATA); + // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } /** diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 65eda209..a5a3b5ef 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -221,17 +221,17 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d spParams.buf = commandBuffer; switch (deviceCommand) { case GET_HK_REPORT: { - prepareEmptyCmd(APID_HK, static_cast(HkServiceIds::GET_REPORT)); + prepareEmptyCmd(Apids::HK, static_cast(HkServiceIds::GET_REPORT)); result = returnvalue::OK; break; } case START_MPSOC: { - prepareEmptyCmd(APID_BOOT_MAN, static_cast(BootManServiceIds::START_MPSOC)); + prepareEmptyCmd(Apids::BOOT_MAN, static_cast(BootManServiceIds::START_MPSOC)); result = returnvalue::OK; break; } case SHUTDOWN_MPSOC: { - prepareEmptyCmd(APID_BOOT_MAN, static_cast(BootManServiceIds::SHUTDOWN_MPSOC)); + prepareEmptyCmd(Apids::BOOT_MAN, static_cast(BootManServiceIds::SHUTDOWN_MPSOC)); result = returnvalue::OK; break; } @@ -241,7 +241,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case RESET_MPSOC: { - prepareEmptyCmd(APID_BOOT_MAN, static_cast(BootManServiceIds::RESET_MPSOC)); + prepareEmptyCmd(Apids::BOOT_MAN, static_cast(BootManServiceIds::RESET_MPSOC)); result = returnvalue::OK; break; } @@ -265,7 +265,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case GET_BOOT_STATUS_REPORT: { - prepareEmptyCmd(APID_BOOT_MAN, + prepareEmptyCmd(Apids::BOOT_MAN, static_cast(BootManServiceIds::GET_BOOT_STATUS_REPORT)); result = returnvalue::OK; break; @@ -298,7 +298,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case GET_LATCHUP_STATUS_REPORT: { - prepareEmptyCmd(APID_LATCHUP_MON, + prepareEmptyCmd(Apids::LATCHUP_MON, static_cast(LatchupMonServiceIds::GET_STATUS_REPORT)); result = returnvalue::OK; break; @@ -380,7 +380,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case FACTORY_FLASH: { - prepareEmptyCmd(APID_BOOT_MAN, static_cast(BootManServiceIds::FACTORY_FLASH)); + prepareEmptyCmd(Apids::BOOT_MAN, static_cast(BootManServiceIds::FACTORY_FLASH)); result = returnvalue::OK; break; } @@ -434,14 +434,14 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case RESET_PL: { - prepareEmptyCmd(APID_BOOT_MAN, static_cast(BootManServiceIds::RESET_PL)); + prepareEmptyCmd(Apids::BOOT_MAN, static_cast(BootManServiceIds::RESET_PL)); result = returnvalue::OK; break; } - case ENABLE_NVMS: { - result = prepareEnableNvmsCommand(commandData); - break; - } + // case ENABLE_NVMS: { + // result = prepareEnableNvmsCommand(commandData); + // break; + // } default: sif::debug << "PlocSupervisorHandler::buildCommandFromCommand: Command not implemented" << std::endl; @@ -1701,18 +1701,18 @@ ReturnValue_t PlocSupervisorHandler::prepareLoggingRequest(const uint8_t* comman 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::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; diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index d731a314..98cd22e9 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -283,7 +283,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { 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 prepareEnableNvmsCommand(const uint8_t* commandData); /** * @brief Copies the content of a space packet to the command buffer. diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index ce197cf4..22484f31 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -499,7 +499,7 @@ ReturnValue_t PlocSupvHelper::selectMemory() { ReturnValue_t PlocSupvHelper::prepareUpdate() { ReturnValue_t result = returnvalue::OK; resetSpParams(); - supv::NoPayloadPacket packet(spParams, supv::APID_BOOT_MAN, + supv::NoPayloadPacket packet(spParams, Apids::BOOT_MAN, static_cast(BootManServiceIds::PREPARE_UPDATE)); result = packet.buildPacket(); if (result != returnvalue::OK) { diff --git a/mission/devices/devicedefinitions/SpBase.h b/mission/devices/devicedefinitions/SpBase.h index 8a5dd079..da2f4cd4 100644 --- a/mission/devices/devicedefinitions/SpBase.h +++ b/mission/devices/devicedefinitions/SpBase.h @@ -24,23 +24,26 @@ struct SpTcParams { 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.fullPayloadLen - 1); + updateLenFromParams(); spParams.creator.setPacketType(ccsds::PacketType::TC); } + void updateLenFromParams() { spParams.creator.setDataLenField(spParams.fullPayloadLen - 1); } const uint8_t* getFullPacket() const { return spParams.buf; } size_t getFullPacketLen() const { return spParams.creator.getFullPacketLen(); } From 8dbb3dcd9b9fa08ee2222e0ab8629ae583415f40 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 7 Nov 2022 17:31:16 +0100 Subject: [PATCH 032/176] continue refactoring --- .../PlocSupervisorDefinitions.h | 329 ++++++++---------- linux/devices/ploc/PlocSupervisorHandler.cpp | 150 ++++---- linux/devices/ploc/PlocSupervisorHandler.h | 4 +- 3 files changed, 218 insertions(+), 265 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index e34f6ab0..128d988c 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -182,7 +182,13 @@ enum class AdcMonServiceIds : uint8_t { COPY_ADC_DATA_TO_MRAM = 0x05 }; -enum class DataLoggerServiceIds : uint8_t { FACTORY_RESET = 0x07 }; +enum class MemManServiceIds : uint8_t { ERASE = 0x01, WRITE = 0x02, CHECK = 0x03 }; + +enum class DataLoggerServiceIds : 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 @@ -744,7 +750,7 @@ class SetAdcEnabledChannels : public TcBase { * @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 @@ -752,11 +758,9 @@ class SetAdcWindowAndStride : public ploc::SpTcBase { * @param windowSize * @param stridingStepSize */ - SetAdcWindowAndStride(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPayloadLen(DATA_FIELD_LENGTH); - // spParams.creator.setApid(APID_SET_ADC_WINDOW_AND_STRIDE); - // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetAdcWindowAndStride(TcParams params) + : TcBase(params, Apids::ADC_MON, static_cast(AdcMonServiceIds::SET_WINDOW_STRIDE), + 4) {} ReturnValue_t buildPacket(uint16_t windowSize, uint16_t stridingStepSize) { auto res = checkSizeAndSerializeHeader(); @@ -768,10 +772,6 @@ class SetAdcWindowAndStride : public ploc::SpTcBase { } 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; @@ -785,18 +785,16 @@ 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.setFullPayloadLen(DATA_FIELD_LENGTH); - // spParams.creator.setApid(APID_SET_ADC_THRESHOLD); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetAdcThreshold(TcParams params) + : TcBase(params, Apids::ADC_MON, static_cast(AdcMonServiceIds::SET_ADC_THRESHOLD), + 4) {} ReturnValue_t buildPacket(uint32_t threshold) { auto res = checkSizeAndSerializeHeader(); @@ -808,11 +806,6 @@ class SetAdcThreshold : public ploc::SpTcBase { } 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), @@ -823,17 +816,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.setFullPayloadLen(DATA_FIELD_LENGTH); - // spParams.creator.setApid(APID_RUN_AUTO_EM_TESTS); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + RunAutoEmTests(TcParams params) + : TcBase(params, Apids::TMTC_MAN, static_cast(TmtcServiceIds::RUN_AUTO_EM_TEST), 1) { } ReturnValue_t buildPacket(uint8_t test) { @@ -846,11 +837,6 @@ class RunAutoEmTests : public ploc::SpTcBase { } 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; } @@ -859,65 +845,62 @@ class RunAutoEmTests : public ploc::SpTcBase { /** * @brief This class packages the space packet to wipe or dump parts of the MRAM. */ -class MramCmd : public ploc::SpTcBase { - 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(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPayloadLen(DATA_FIELD_LENGTH); - // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } - - 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"; - } - auto res = checkSizeAndSerializeHeader(); - if (res != returnvalue::OK) { - return res; - } - initPacket(start, stop); - 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)); - } -}; +// 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, Apids::DATA_LOGGER) { +// setLenFromPayloadLen(6); +// } +// +// ReturnValue_t buildPacket(uint32_t start, uint32_t stop, MramAction action) { +// if (action == MramAction::WIPE) { +// setServiceId(static_cast(DataLoggerServiceIds::WIPE_MRAM)); +// } else if (action == MramAction::DUMP) { +// setServiceId(static_cast(DataLoggerServiceIds::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 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 @@ -926,11 +909,8 @@ class SetGpio : public ploc::SpTcBase { * @param pin * @param val */ - SetGpio(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPayloadLen(DATA_FIELD_LENGTH); - // spParams.creator.setApid(APID_SET_GPIO); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetGpio(TcParams params) + : TcBase(params, Apids::TMTC_MAN, static_cast(TmtcServiceIds::SET_GPIO), 3) {} ReturnValue_t buildPacket(uint8_t port, uint8_t pin, uint8_t val) { auto res = checkSizeAndSerializeHeader(); @@ -942,11 +922,6 @@ class SetGpio : public ploc::SpTcBase { } 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; @@ -962,7 +937,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 @@ -970,11 +945,8 @@ class ReadGpio : public ploc::SpTcBase { * @param port * @param pin */ - ReadGpio(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPayloadLen(DATA_FIELD_LENGTH); - // spParams.creator.setApid(APID_READ_GPIO); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + ReadGpio(TcParams params) + : TcBase(params, Apids::TMTC_MAN, static_cast(TmtcServiceIds::READ_GPIO), 2) {} ReturnValue_t buildPacket(uint8_t port, uint8_t pin) { auto res = checkSizeAndSerializeHeader(); @@ -986,11 +958,6 @@ class ReadGpio : public ploc::SpTcBase { } 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; @@ -1008,57 +975,56 @@ class ReadGpio : public ploc::SpTcBase { * OP = 0x01: Only the mirror entries will be wiped. * OP = 0x02: Only the circular entries will be wiped. */ -class FactoryReset : public ploc::SpTcBase { +// class FactoryReset : public TcBase { +// public: +// enum class Op { CLEAR_ALL, MIRROR_ENTRIES, CIRCULAR_ENTRIES }; +// +// /** +// * @brief Constructor +// * +// * @param op +// */ +// FactoryReset(TcParams params) +// : TcBase(params, Apids::TMTC_MAN, static_cast(TmtcServiceIds::)) { +// // 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 calcAndSetCrc(); +// } +// +// 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.setFullPayloadLen(packetDataLen); +// } +// }; + +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 calcAndSetCrc(); - } - - 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.setFullPayloadLen(packetDataLen); - } -}; - -class SetShutdownTimeout : public ploc::SpTcBase { - public: - SetShutdownTimeout(ploc::SpTcParams params) : ploc::SpTcBase(params) { - spParams.setFullPayloadLen(PAYLOAD_LEN + 2); - // spParams.creator.setApid(APID_SET_SHUTDOWN_TIMEOUT); - // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + SetShutdownTimeout(TcParams params) + : TcBase(params, Apids::BOOT_MAN, static_cast(BootManServiceIds::SHUTDOWN_TIMEOUT), + 4) {} ReturnValue_t buildPacket(uint32_t timeout) { auto res = checkSizeAndSerializeHeader(); @@ -1070,10 +1036,6 @@ class SetShutdownTimeout : public ploc::SpTcBase { } 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), @@ -1084,7 +1046,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 @@ -1093,11 +1055,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.setFullPayloadLen(PAYLOAD_LENGTH + 2); - // spParams.creator.setApid(APID_CHECK_MEMORY); - // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + CheckMemory(TcParams params) + : TcBase(params, Apids::MEM_MAN, static_cast(MemManServiceIds::CHECK), 10) {} ReturnValue_t buildPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { auto res = checkSizeAndSerializeHeader(); @@ -1109,8 +1068,6 @@ class CheckMemory : public ploc::SpTcBase { } private: - static const uint16_t PAYLOAD_LENGTH = 10; // length without CRC field - uint8_t memoryId = 0; uint8_t n = 1; uint32_t startAddress = 0; @@ -1132,7 +1089,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 @@ -1141,10 +1098,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, Apids::MEM_MAN, static_cast(MemManServiceIds::WRITE), 1) {} ReturnValue_t buildPacket(ccsds::SequenceFlags seqFlags, uint16_t sequenceCount, uint8_t memoryId, uint32_t startAddress, uint16_t length, uint8_t* updateData) { @@ -1173,9 +1128,9 @@ class WriteMemory : public ploc::SpTcBase { uint8_t* updateData) { uint8_t* data = payloadStart; if (updateDataLen % 2 != 0) { - spParams.setFullPayloadLen(META_DATA_LENGTH + updateDataLen + 1 + 2); + setLenFromPayloadLen(META_DATA_LENGTH + updateDataLen + 1); } else { - spParams.setFullPayloadLen(META_DATA_LENGTH + updateDataLen + 2); + setLenFromPayloadLen(META_DATA_LENGTH + updateDataLen); } // To avoid crashes in this unexpected case ReturnValue_t result = checkPayloadLen(); @@ -1204,13 +1159,11 @@ class WriteMemory : public ploc::SpTcBase { /** * @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.setFullPayloadLen(PAYLOAD_LENGTH + 2); - // spParams.creator.setApid(APID_ERASE_MEMORY); - // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } + EraseMemory(TcParams params) + : TcBase(params, Apids::MEM_MAN, static_cast(MemManServiceIds::ERASE), + PAYLOAD_LENGTH) {} ReturnValue_t buildPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { auto res = checkSizeAndSerializeHeader(); @@ -1246,9 +1199,9 @@ class EraseMemory : public ploc::SpTcBase { /** * @brief This class creates the space packet to enable the auto TM generation */ -class EnableAutoTm : public ploc::SpTcBase { +class EnableAutoTm : public TcBase { public: - EnableAutoTm(ploc::SpTcParams params) : ploc::SpTcBase(params) { + EnableAutoTm(TcParams params) : TcBase(params) { spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); // spParams.creator.setApid(APID_AUTO_TM); // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -1271,9 +1224,9 @@ class EnableAutoTm : public ploc::SpTcBase { /** * @brief This class creates the space packet to disable the auto TM generation */ -class DisableAutoTm : public ploc::SpTcBase { +class DisableAutoTm : public TcBase { public: - DisableAutoTm(ploc::SpTcParams params) : ploc::SpTcBase(params) { + DisableAutoTm(TcParams params) : TcBase(params) { spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); // spParams.creator.setApid(APID_AUTO_TM); // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -1296,7 +1249,7 @@ class DisableAutoTm : public ploc::SpTcBase { /** * @brief This class creates the space packet to request the logging data from the supervisor */ -class RequestLoggingData : public ploc::SpTcBase { +class RequestLoggingData : public TcBase { public: /** * Subapid @@ -1308,7 +1261,7 @@ class RequestLoggingData : public ploc::SpTcBase { SET_LOGGING_TOPIC = 4 /**< SET_LOGGING_TOPIC */ }; - RequestLoggingData(ploc::SpTcParams params) : ploc::SpTcBase(params) { + RequestLoggingData(TcParams params) : TcBase(params) { spParams.setFullPayloadLen(PAYLOAD_LENGTH + 2); // spParams.creator.setApid(APID_REQUEST_LOGGING_DATA); // spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index a5a3b5ef..36898215 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -318,14 +318,14 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d result = prepareRunAutoEmTest(commandData); break; } - case WIPE_MRAM: { - result = prepareWipeMramCmd(commandData); - break; - } - case FIRST_MRAM_DUMP: - case CONSECUTIVE_MRAM_DUMP: - result = prepareDumpMramCmd(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; @@ -341,33 +341,33 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d // 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 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; + }*/ // Removed command // case START_MPSOC_QUIET: { // prepareEmptyCmd(APID_START_MPSOC_QUIET); @@ -1594,47 +1594,47 @@ 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::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::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; diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 98cd22e9..08c0e846 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -278,8 +278,8 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t prepareSetAdcWindowAndStrideCmd(const uint8_t* commandData); 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 prepareWipeMramCmd(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); From 3b575acd5518da9ca56a96c512409e5b823cf894 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 10:10:57 +0100 Subject: [PATCH 033/176] comment out more code which was removed --- .../PlocSupervisorDefinitions.h | 530 +++++++++--------- linux/devices/ploc/PlocSupervisorHandler.cpp | 253 ++++----- linux/devices/ploc/PlocSupervisorHandler.h | 8 +- linux/devices/ploc/PlocSupvUartMan.cpp | 97 ++-- linux/devices/ploc/PlocSupvUartMan.h | 2 +- 5 files changed, 437 insertions(+), 453 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 128d988c..cd128ca0 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -445,45 +445,6 @@ class MPSoCBootSelect : public TcBase { } }; -/** - * @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.setFullPayloadLen(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 calcAndSetCrc(); -// } -// -// 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; -// } -// }; - /** * @brief This class generates the space packet to update the time of the PLOC supervisor. */ @@ -715,37 +676,6 @@ class SetAlertlimit : public TcBase { } }; -/** - * @brief This class packages the space packet to enable or disable ADC channels. - */ -class SetAdcEnabledChannels : public TcBase { - public: - /** - * @brief Constructor - * - * @param ch Defines channels to be enabled or disabled. - */ - SetAdcEnabledChannels(TcParams params) - : TcBase(params, Apids::ADC_MON, static_cast(AdcMonServiceIds::SET_ENABLED_CHANNELS), - 2) {} - - ReturnValue_t buildPacket(uint16_t ch) { - auto res = checkSizeAndSerializeHeader(); - if (res != returnvalue::OK) { - return res; - } - initPacket(ch); - return calcAndSetCrc(); - } - - private: - 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. @@ -842,60 +772,6 @@ class RunAutoEmTests : public TcBase { void initPacket(uint8_t test) { payloadStart[0] = test; } }; -/** - * @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, Apids::DATA_LOGGER) { -// setLenFromPayloadLen(6); -// } -// -// ReturnValue_t buildPacket(uint32_t start, uint32_t stop, MramAction action) { -// if (action == MramAction::WIPE) { -// setServiceId(static_cast(DataLoggerServiceIds::WIPE_MRAM)); -// } else if (action == MramAction::DUMP) { -// setServiceId(static_cast(DataLoggerServiceIds::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 packages the space packet change the state of a GPIO. This command is only * required for ground testing. @@ -967,59 +843,6 @@ class ReadGpio : public TcBase { } }; -/** - * @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, Apids::TMTC_MAN, static_cast(TmtcServiceIds::)) { -// // 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 calcAndSetCrc(); -// } -// -// 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.setFullPayloadLen(packetDataLen); -// } -// }; - class SetShutdownTimeout : public TcBase { public: SetShutdownTimeout(TcParams params) @@ -1068,10 +891,7 @@ class CheckMemory : public TcBase { } private: - 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; @@ -1177,10 +997,7 @@ class EraseMemory : public TcBase { 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; @@ -1196,97 +1013,6 @@ class EraseMemory : public TcBase { } }; -/** - * @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; -}; - class VerificationReport : public ploc::SpTmReader { public: VerificationReport(const uint8_t* buf, size_t maxSize) : ploc::SpTmReader(buf, maxSize) {} @@ -1961,6 +1687,262 @@ 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, Apids::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, Apids::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 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, Apids::DATA_LOGGER) { setLenFromPayloadLen(6); } + + ReturnValue_t buildPacket(uint32_t start, uint32_t stop, MramAction action) { + if (action == MramAction::WIPE) { + setServiceId(static_cast(DataLoggerServiceIds::WIPE_MRAM)); + } else if (action == MramAction::DUMP) { + setServiceId(static_cast(DataLoggerServiceIds::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 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 packages the space packet to enable or disable ADC channels. + */ +class SetAdcEnabledChannels : public TcBase { + public: + /** + * @brief Constructor + * + * @param ch Defines channels to be enabled or disabled. + */ + SetAdcEnabledChannels(TcParams params) + : TcBase(params, Apids::ADC_MON, static_cast(AdcMonServiceIds::SET_ENABLED_CHANNELS), + 2) {} + + ReturnValue_t buildPacket(uint16_t ch) { + auto res = checkSizeAndSerializeHeader(); + if (res != returnvalue::OK) { + return res; + } + initPacket(ch); + return calcAndSetCrc(); + } + + private: + void initPacket(uint16_t ch) { + size_t serializedSize = 0; + SerializeAdapter::serialize(&ch, &payloadStart, &serializedSize, sizeof(ch), + SerializeIF::Endianness::BIG); + } +}; + +/** + * @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; +}; + +} // namespace notimpl + } // namespace supv #endif /* MISSION_DEVICES_DEVICEDEFINITIONS_PLOCSVPDEFINITIONS_H_ */ diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 36898215..cf63bea3 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -282,21 +282,21 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d result = prepareSetAlertLimitCmd(commandData); break; } - case SET_ADC_ENABLED_CHANNELS: { - prepareSetAdcEnabledChannelsCmd(commandData); - result = returnvalue::OK; - break; - } - case SET_ADC_WINDOW_AND_STRIDE: { - prepareSetAdcWindowAndStrideCmd(commandData); - result = returnvalue::OK; - break; - } - case SET_ADC_THRESHOLD: { - prepareSetAdcThresholdCmd(commandData); - result = returnvalue::OK; - break; - } + // case SET_ADC_ENABLED_CHANNELS: { + // prepareSetAdcEnabledChannelsCmd(commandData); + // result = returnvalue::OK; + // break; + // } + // case SET_ADC_WINDOW_AND_STRIDE: { + // prepareSetAdcWindowAndStrideCmd(commandData); + // result = returnvalue::OK; + // break; + // } + // case SET_ADC_THRESHOLD: { + // prepareSetAdcThresholdCmd(commandData); + // result = returnvalue::OK; + // break; + // } case GET_LATCHUP_STATUS_REPORT: { prepareEmptyCmd(Apids::LATCHUP_MON, static_cast(LatchupMonServiceIds::GET_STATUS_REPORT)); @@ -384,55 +384,55 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d 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 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(Apids::BOOT_MAN, static_cast(BootManServiceIds::RESET_PL)); result = returnvalue::OK; @@ -744,10 +744,10 @@ ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id, result = handleLatchupStatusReport(packet); break; } - case (LOGGING_REPORT): { - result = handleLoggingReport(packet); - break; - } + // case (LOGGING_REPORT): { + // result = handleLoggingReport(packet); + // break; + // } case (ADC_REPORT): { result = handleAdcReport(packet); break; @@ -1248,41 +1248,41 @@ 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::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; -} +// 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; +// } ReturnValue_t PlocSupervisorHandler::handleAdcReport(const uint8_t* data) { ReturnValue_t result = returnvalue::OK; @@ -1543,16 +1543,17 @@ ReturnValue_t PlocSupervisorHandler::prepareSetAlertLimitCmd(const uint8_t* comm return returnvalue::OK; } -ReturnValue_t PlocSupervisorHandler::prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData) { - uint16_t ch = *(commandData) << 8 | *(commandData + 1); - supv::SetAdcEnabledChannels packet(spParams); - ReturnValue_t result = packet.buildPacket(ch); - if (result != returnvalue::OK) { - return result; - } - finishTcPrep(packet.getFullPacketLen()); - return returnvalue::OK; -} +// ReturnValue_t PlocSupervisorHandler::prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData) +// { +// uint16_t ch = *(commandData) << 8 | *(commandData + 1); +// supv::SetAdcEnabledChannels packet(spParams); +// ReturnValue_t result = packet.buildPacket(ch); +// if (result != returnvalue::OK) { +// return result; +// } +// finishTcPrep(packet.getFullPacketLen()); +// return returnvalue::OK; +// } ReturnValue_t PlocSupervisorHandler::prepareSetAdcWindowAndStrideCmd(const uint8_t* commandData) { uint8_t offset = 0; @@ -1687,19 +1688,19 @@ 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::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; diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 08c0e846..21ae743d 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -211,7 +211,7 @@ 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); + // ReturnValue_t handleLoggingReport(const uint8_t* data); ReturnValue_t handleAdcReport(const uint8_t* data); /** @@ -274,7 +274,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t prepareLatchupConfigCmd(const uint8_t* commandData, DeviceCommandId_t deviceCommand); ReturnValue_t prepareSetAlertLimitCmd(const uint8_t* commandData); - ReturnValue_t prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData); + // ReturnValue_t prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData); ReturnValue_t prepareSetAdcWindowAndStrideCmd(const uint8_t* commandData); ReturnValue_t prepareSetAdcThresholdCmd(const uint8_t* commandData); ReturnValue_t prepareRunAutoEmTest(const uint8_t* commandData); @@ -282,8 +282,8 @@ class PlocSupervisorHandler : public DeviceHandlerBase { // 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. diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 22484f31..3632a21f 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -428,45 +428,46 @@ 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::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; @@ -916,15 +917,15 @@ ReturnValue_t PlocSupvHelper::handleRunningLongerRequest() { 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); - } + // 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: { diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index c0f23f22..d36234e2 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -268,7 +268,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, ReturnValue_t continueUpdate(); ReturnValue_t updateOperation(); ReturnValue_t writeUpdatePackets(); - ReturnValue_t performEventBufferRequest(); + // ReturnValue_t performEventBufferRequest(); ReturnValue_t handlePacketTransmission(ploc::SpTcBase& packet, uint32_t timeoutExecutionReport = 60000); ReturnValue_t sendCommand(ploc::SpTcBase& packet); From 4bf22f689a8205a3165c115b62005b8169bf6432 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 10:22:57 +0100 Subject: [PATCH 034/176] create TM base class --- .../PlocSupervisorDefinitions.h | 21 ++++++++++++++++++- linux/devices/ploc/PlocSupvUartMan.cpp | 5 +++-- mission/devices/devicedefinitions/SpBase.h | 5 ----- 3 files changed, 23 insertions(+), 8 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index cd128ca0..4d8dbb46 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -226,7 +226,7 @@ static const size_t MAX_DATA_CAPACITY = 1016; static const size_t MAX_PACKET_SIZE = 1024; static constexpr size_t MIN_PAYLOAD_LEN = SECONDARY_HEADER_LEN + CRC_LEN; -static constexpr size_t MIN_TC_LEN = ccsds::HEADER_LEN + MIN_PAYLOAD_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; struct UpdateParams { @@ -386,6 +386,25 @@ class TcBase : public ploc::SpTcBase { } }; +class TmBase: public ploc::SpTmReader { +public: + 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; + } + } + + uint8_t getServiceId() { + return getPacketData()[TIMESTAMP_LEN]; + } + + const uint8_t* getPayloadStart() { + return getPacketData() + SECONDARY_HEADER_LEN; + } +private: + +}; + class NoPayloadPacket : public TcBase { public: NoPayloadPacket(TcParams params, uint16_t apid, uint8_t serviceId) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 3632a21f..604a6c5e 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -859,8 +859,9 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception(ploc::SpTmReader& reade file.close(); return EVENT_BUFFER_REPLY_INVALID_APID; } - file.write(reinterpret_cast(reader.getPacketData()), - reader.getPayloadDataLength()); + // TODO: Fix +// file.write(reinterpret_cast(reader.getPacketData()), +// reader.getPayloadDataLength()); } return result; } diff --git a/mission/devices/devicedefinitions/SpBase.h b/mission/devices/devicedefinitions/SpBase.h index da2f4cd4..6cd4a803 100644 --- a/mission/devices/devicedefinitions/SpBase.h +++ b/mission/devices/devicedefinitions/SpBase.h @@ -102,11 +102,6 @@ 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() { if (CRC::crc16ccitt(getFullData(), getFullPacketLen()) != 0) { return returnvalue::FAILED; From 4515703efa01a884ec3d75e903c40aa8376216ec Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 11:08:21 +0100 Subject: [PATCH 035/176] added tm service IDs --- fsfw | 2 +- .../PlocSupervisorDefinitions.h | 260 +++++++++++------- linux/devices/ploc/PlocSupervisorHandler.cpp | 240 ++++++++-------- linux/devices/ploc/PlocSupvUartMan.cpp | 88 +++--- mission/devices/devicedefinitions/SpBase.h | 2 +- 5 files changed, 329 insertions(+), 263 deletions(-) diff --git a/fsfw b/fsfw index 672fca51..0e8f5ddd 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 672fca5169b017387e58e2ff864913d932c59aa1 +Subproject commit 0e8f5ddd26d586dd40e69f52aef1a63c0d5a9da6 diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 4d8dbb46..c564b6e4 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -17,6 +17,12 @@ using namespace returnvalue; namespace supv { +static const uint8_t CLASS_ID = CLASS_ID::PLOC_SUPERVISOR_HANDLER; + +static constexpr ReturnValue_t CRC_MISSMATCH = makeCode(CLASS_ID, 1); +static constexpr ReturnValue_t APID_MISSMATCH = makeCode(CLASS_ID, 2); +static constexpr ReturnValue_t BUF_TOO_SMALL = makeCode(CLASS_ID, 3); + 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 @@ -135,14 +141,16 @@ enum Apids { WDOG_MAN = 0x07 }; -enum class HkServiceIds : uint8_t { +namespace tc { + +enum class HkId : uint8_t { ENABLE = 0x01, SET_PERIOD = 0x02, GET_REPORT = 0x03, GET_HARDFAULTS_REPORT = 0x04, }; -enum class TmtcServiceIds : uint8_t { +enum class TmtcId : uint8_t { TIME_REF = 0x03, GET_SUPV_VERSION = 0x05, RUN_AUTO_EM_TEST = 0x08, @@ -151,7 +159,7 @@ enum class TmtcServiceIds : uint8_t { GET_MPSOC_POWER_INFO = 0x10 }; -enum class BootManServiceIds : uint8_t { +enum class BootManId : uint8_t { START_MPSOC = 0x01, SHUTDOWN_MPSOC = 0x02, SELECT_IMAGE = 0x03, @@ -165,7 +173,7 @@ enum class BootManServiceIds : uint8_t { FACTORY_FLASH = 0x0C }; -enum class LatchupMonServiceIds : uint8_t { +enum class LatchupMonId : uint8_t { ENABLE = 0x01, DISABLE = 0x02, SET_ALERT_LIMIT = 0x04, @@ -174,7 +182,7 @@ enum class LatchupMonServiceIds : uint8_t { // Right now, none of the commands seem to be implemented, but still // keep the enum here in case some are added -enum class AdcMonServiceIds : uint8_t { +enum class AdcMonId : uint8_t { SET_SWEEP_PERIOD = 0x01, SET_ENABLED_CHANNELS = 0x02, SET_WINDOW_STRIDE = 0x03, @@ -182,9 +190,9 @@ enum class AdcMonServiceIds : uint8_t { COPY_ADC_DATA_TO_MRAM = 0x05 }; -enum class MemManServiceIds : uint8_t { ERASE = 0x01, WRITE = 0x02, CHECK = 0x03 }; +enum class MemManId : uint8_t { ERASE = 0x01, WRITE = 0x02, CHECK = 0x03 }; -enum class DataLoggerServiceIds : uint8_t { +enum class DataLoggerServiceId : uint8_t { WIPE_MRAM = 0x05, DUMP_MRAM = 0x06, FACTORY_RESET = 0x07 @@ -192,7 +200,23 @@ enum class DataLoggerServiceIds : uint8_t { // Right now, none of the commands seem to be implemented, but still // keep the enum here in case some are added -enum class WdogManServiceIds : uint8_t {}; +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 static const uint16_t APID_MASK = 0x3FF; static const uint16_t SEQUENCE_COUNT_MASK = 0xFFF; @@ -209,11 +233,11 @@ 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 { +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; -} // namespace recv_timeout +} // namespace timeout static constexpr size_t TIMESTAMP_LEN = 7; static constexpr size_t SECONDARY_HEADER_LEN = TIMESTAMP_LEN + 1; @@ -386,23 +410,29 @@ class TcBase : public ploc::SpTcBase { } }; -class TmBase: public ploc::SpTmReader { -public: - TmBase(const uint8_t* data, size_t maxSize): ploc::SpTmReader(data, maxSize) { - if(maxSize < MIN_TMTC_LEN) { +class TmBase : public ploc::SpTmReader { + public: + 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; } } - uint8_t getServiceId() { - return getPacketData()[TIMESTAMP_LEN]; + bool verifyCrc() { + if (checkCrc() == returnvalue::OK) { + crcOk = true; + } + return crcOk; } - const uint8_t* getPayloadStart() { - return getPacketData() + SECONDARY_HEADER_LEN; - } -private: + bool crcIsOk() const { return crcOk; } + uint8_t getServiceId() const { return getPacketData()[TIMESTAMP_LEN]; } + + const uint8_t* getPayloadStart() const { return getPacketData() + SECONDARY_HEADER_LEN; } + + private: + bool crcOk = false; }; class NoPayloadPacket : public TcBase { @@ -444,7 +474,7 @@ class MPSoCBootSelect : public TcBase { * @note Selection of partitions is currently not supported. */ MPSoCBootSelect(TcParams params) - : TcBase(params, Apids::BOOT_MAN, static_cast(BootManServiceIds::SELECT_IMAGE), 4) {} + : TcBase(params, Apids::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(); @@ -471,7 +501,7 @@ class SetTimeRef : public TcBase { public: static constexpr size_t PAYLOAD_LEN = 8; SetTimeRef(TcParams params) - : TcBase(params, Apids::TMTC_MAN, static_cast(TmtcServiceIds::TIME_REF), 8) {} + : TcBase(params, Apids::TMTC_MAN, static_cast(tc::TmtcId::TIME_REF), 8) {} ReturnValue_t buildPacket(Clock::TimeOfDay_t* time) { auto res = checkSizeAndSerializeHeader(); @@ -546,7 +576,7 @@ class SetBootTimeout : public TcBase { * @param timeout The boot timeout in milliseconds. */ SetBootTimeout(TcParams params) - : TcBase(params, Apids::BOOT_MAN, static_cast(BootManServiceIds::SET_BOOT_TIMEOUT), + : TcBase(params, Apids::BOOT_MAN, static_cast(tc::BootManId::SET_BOOT_TIMEOUT), PAYLOAD_LEN) {} ReturnValue_t buildPacket(uint32_t timeout) { @@ -578,8 +608,8 @@ class SetRestartTries : public TcBase { * @param restartTries Maximum restart tries to set. */ SetRestartTries(TcParams params) - : TcBase(params, Apids::BOOT_MAN, - static_cast(BootManServiceIds::SET_MAX_REBOOT_TRIES), 1) {} + : TcBase(params, Apids::BOOT_MAN, static_cast(tc::BootManId::SET_MAX_REBOOT_TRIES), + 1) {} ReturnValue_t buildPacket(uint8_t restartTries) { auto res = checkSizeAndSerializeHeader(); @@ -607,7 +637,7 @@ class DisablePeriodicHkTransmission : public TcBase { * @brief Constructor */ DisablePeriodicHkTransmission(TcParams params) - : TcBase(params, Apids::HK, static_cast(HkServiceIds::ENABLE), 1) {} + : TcBase(params, Apids::HK, static_cast(tc::HkId::ENABLE), 1) {} ReturnValue_t buildPacket() { auto res = checkSizeAndSerializeHeader(); @@ -640,9 +670,9 @@ class LatchupAlert : public TcBase { ReturnValue_t buildPacket(bool state, uint8_t latchupId) { if (state) { - setServiceId(static_cast(LatchupMonServiceIds::ENABLE)); + setServiceId(static_cast(tc::LatchupMonId::ENABLE)); } else { - setServiceId(static_cast(LatchupMonServiceIds::DISABLE)); + setServiceId(static_cast(tc::LatchupMonId::DISABLE)); } auto res = checkSizeAndSerializeHeader(); if (res != returnvalue::OK) { @@ -668,8 +698,8 @@ class SetAlertlimit : public TcBase { * @param dutycycle */ SetAlertlimit(TcParams params) - : TcBase(params, Apids::LATCHUP_MON, - static_cast(LatchupMonServiceIds::SET_ALERT_LIMIT), 5) {} + : TcBase(params, Apids::LATCHUP_MON, static_cast(tc::LatchupMonId::SET_ALERT_LIMIT), + 5) {} ReturnValue_t buildPacket(uint8_t latchupId, uint32_t dutycycle) { auto res = checkSizeAndSerializeHeader(); @@ -708,8 +738,7 @@ class SetAdcWindowAndStride : public TcBase { * @param stridingStepSize */ SetAdcWindowAndStride(TcParams params) - : TcBase(params, Apids::ADC_MON, static_cast(AdcMonServiceIds::SET_WINDOW_STRIDE), - 4) {} + : TcBase(params, Apids::ADC_MON, static_cast(tc::AdcMonId::SET_WINDOW_STRIDE), 4) {} ReturnValue_t buildPacket(uint16_t windowSize, uint16_t stridingStepSize) { auto res = checkSizeAndSerializeHeader(); @@ -742,8 +771,7 @@ class SetAdcThreshold : public TcBase { * @param threshold */ SetAdcThreshold(TcParams params) - : TcBase(params, Apids::ADC_MON, static_cast(AdcMonServiceIds::SET_ADC_THRESHOLD), - 4) {} + : TcBase(params, Apids::ADC_MON, static_cast(tc::AdcMonId::SET_ADC_THRESHOLD), 4) {} ReturnValue_t buildPacket(uint32_t threshold) { auto res = checkSizeAndSerializeHeader(); @@ -773,8 +801,7 @@ class RunAutoEmTests : public TcBase { * @param test 1 - complete EM test, 2 - Short test (only memory readback NVM0,1,3) */ RunAutoEmTests(TcParams params) - : TcBase(params, Apids::TMTC_MAN, static_cast(TmtcServiceIds::RUN_AUTO_EM_TEST), 1) { - } + : TcBase(params, Apids::TMTC_MAN, static_cast(tc::TmtcId::RUN_AUTO_EM_TEST), 1) {} ReturnValue_t buildPacket(uint8_t test) { auto res = checkSizeAndSerializeHeader(); @@ -805,7 +832,7 @@ class SetGpio : public TcBase { * @param val */ SetGpio(TcParams params) - : TcBase(params, Apids::TMTC_MAN, static_cast(TmtcServiceIds::SET_GPIO), 3) {} + : TcBase(params, Apids::TMTC_MAN, static_cast(tc::TmtcId::SET_GPIO), 3) {} ReturnValue_t buildPacket(uint8_t port, uint8_t pin, uint8_t val) { auto res = checkSizeAndSerializeHeader(); @@ -841,7 +868,7 @@ class ReadGpio : public TcBase { * @param pin */ ReadGpio(TcParams params) - : TcBase(params, Apids::TMTC_MAN, static_cast(TmtcServiceIds::READ_GPIO), 2) {} + : TcBase(params, Apids::TMTC_MAN, static_cast(tc::TmtcId::READ_GPIO), 2) {} ReturnValue_t buildPacket(uint8_t port, uint8_t pin) { auto res = checkSizeAndSerializeHeader(); @@ -865,8 +892,7 @@ class ReadGpio : public TcBase { class SetShutdownTimeout : public TcBase { public: SetShutdownTimeout(TcParams params) - : TcBase(params, Apids::BOOT_MAN, static_cast(BootManServiceIds::SHUTDOWN_TIMEOUT), - 4) {} + : TcBase(params, Apids::BOOT_MAN, static_cast(tc::BootManId::SHUTDOWN_TIMEOUT), 4) {} ReturnValue_t buildPacket(uint32_t timeout) { auto res = checkSizeAndSerializeHeader(); @@ -898,7 +924,7 @@ class CheckMemory : public TcBase { * @param length Length in bytes of memory region */ CheckMemory(TcParams params) - : TcBase(params, Apids::MEM_MAN, static_cast(MemManServiceIds::CHECK), 10) {} + : TcBase(params, Apids::MEM_MAN, static_cast(tc::MemManId::CHECK), 10) {} ReturnValue_t buildPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { auto res = checkSizeAndSerializeHeader(); @@ -938,7 +964,7 @@ class WriteMemory : public TcBase { * @param updateData Pointer to buffer containing update data */ WriteMemory(TcParams params) - : TcBase(params, Apids::MEM_MAN, static_cast(MemManServiceIds::WRITE), 1) {} + : TcBase(params, Apids::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) { @@ -1001,8 +1027,7 @@ class WriteMemory : public TcBase { class EraseMemory : public TcBase { public: EraseMemory(TcParams params) - : TcBase(params, Apids::MEM_MAN, static_cast(MemManServiceIds::ERASE), - PAYLOAD_LENGTH) {} + : TcBase(params, Apids::MEM_MAN, static_cast(tc::MemManId::ERASE), PAYLOAD_LENGTH) {} ReturnValue_t buildPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { auto res = checkSizeAndSerializeHeader(); @@ -1032,61 +1057,95 @@ class EraseMemory : public TcBase { } }; -class VerificationReport : public ploc::SpTmReader { +class VerificationReport { public: - VerificationReport(const uint8_t* buf, size_t maxSize) : ploc::SpTmReader(buf, maxSize) {} + VerificationReport(TmBase& readerBase) : readerBase(readerBase) {} + + virtual ~VerificationReport() = default; + + virtual ReturnValue_t parse() { + if (not readerBase.crcIsOk()) { + return CRC_MISSMATCH; + } + if (readerBase.getApid() != Apids::TMTC_MAN) { + return APID_MISSMATCH; + } + if (readerBase.getBufSize() < MIN_PAYLOAD_LEN + 8) { + sif::error << "VerificationReport: Invalid verification report, payload too small" + << std::endl; + return BUF_TOO_SMALL; + } + 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; + } /** * @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; - } - return refApid; - } + uint8_t getRefApid() const { 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; - } + uint8_t getRefServiceId() const { return refServiceId; } + + uint16_t getRefSequenceCount() const { return refSeqCount; } + + uint32_t getStatusCode() const { return statusCode; } virtual ReturnValue_t checkApid() { return returnvalue::FAILED; } private: - static const uint8_t OFFSET_STATUS_CODE = 4; + 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() != ) + // 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; + // } + return OK; } void printStatusInformation() { @@ -1147,20 +1206,21 @@ class AcknowledgmentReport : public VerificationReport { 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; - } + ReturnValue_t parse() override { + /* 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; + }*/ + return OK; } private: @@ -1808,9 +1868,9 @@ class MramCmd : public TcBase { ReturnValue_t buildPacket(uint32_t start, uint32_t stop, MramAction action) { if (action == MramAction::WIPE) { - setServiceId(static_cast(DataLoggerServiceIds::WIPE_MRAM)); + setServiceId(static_cast(tc::DataLoggerServiceId::WIPE_MRAM)); } else if (action == MramAction::DUMP) { - setServiceId(static_cast(DataLoggerServiceIds::DUMP_MRAM)); + setServiceId(static_cast(tc::DataLoggerServiceId::DUMP_MRAM)); } else { sif::debug << "WipeMram: Invalid action specified"; } @@ -1899,7 +1959,7 @@ class SetAdcEnabledChannels : public TcBase { * @param ch Defines channels to be enabled or disabled. */ SetAdcEnabledChannels(TcParams params) - : TcBase(params, Apids::ADC_MON, static_cast(AdcMonServiceIds::SET_ENABLED_CHANNELS), + : TcBase(params, Apids::ADC_MON, static_cast(tc::AdcMonId::SET_ENABLED_CHANNELS), 2) {} ReturnValue_t buildPacket(uint16_t ch) { diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index cf63bea3..f26012a7 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -221,17 +221,17 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d spParams.buf = commandBuffer; switch (deviceCommand) { case GET_HK_REPORT: { - prepareEmptyCmd(Apids::HK, static_cast(HkServiceIds::GET_REPORT)); + prepareEmptyCmd(Apids::HK, static_cast(tc::HkId::GET_REPORT)); result = returnvalue::OK; break; } case START_MPSOC: { - prepareEmptyCmd(Apids::BOOT_MAN, static_cast(BootManServiceIds::START_MPSOC)); + prepareEmptyCmd(Apids::BOOT_MAN, static_cast(tc::BootManId::START_MPSOC)); result = returnvalue::OK; break; } case SHUTDOWN_MPSOC: { - prepareEmptyCmd(Apids::BOOT_MAN, static_cast(BootManServiceIds::SHUTDOWN_MPSOC)); + prepareEmptyCmd(Apids::BOOT_MAN, static_cast(tc::BootManId::SHUTDOWN_MPSOC)); result = returnvalue::OK; break; } @@ -241,7 +241,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case RESET_MPSOC: { - prepareEmptyCmd(Apids::BOOT_MAN, static_cast(BootManServiceIds::RESET_MPSOC)); + prepareEmptyCmd(Apids::BOOT_MAN, static_cast(tc::BootManId::RESET_MPSOC)); result = returnvalue::OK; break; } @@ -265,8 +265,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case GET_BOOT_STATUS_REPORT: { - prepareEmptyCmd(Apids::BOOT_MAN, - static_cast(BootManServiceIds::GET_BOOT_STATUS_REPORT)); + prepareEmptyCmd(Apids::BOOT_MAN, static_cast(tc::BootManId::GET_BOOT_STATUS_REPORT)); result = returnvalue::OK; break; } @@ -299,7 +298,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d // } case GET_LATCHUP_STATUS_REPORT: { prepareEmptyCmd(Apids::LATCHUP_MON, - static_cast(LatchupMonServiceIds::GET_STATUS_REPORT)); + static_cast(tc::LatchupMonId::GET_STATUS_REPORT)); result = returnvalue::OK; break; } @@ -380,7 +379,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case FACTORY_FLASH: { - prepareEmptyCmd(Apids::BOOT_MAN, static_cast(BootManServiceIds::FACTORY_FLASH)); + prepareEmptyCmd(Apids::BOOT_MAN, static_cast(tc::BootManId::FACTORY_FLASH)); result = returnvalue::OK; break; } @@ -434,7 +433,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d // break; // } case RESET_PL: { - prepareEmptyCmd(Apids::BOOT_MAN, static_cast(BootManServiceIds::RESET_PL)); + prepareEmptyCmd(Apids::BOOT_MAN, static_cast(tc::BootManId::RESET_PL)); result = returnvalue::OK; break; } @@ -930,56 +929,57 @@ 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) { - 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); - 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; - } - } + // TODO: Fix + // AcknowledgmentReport ack(data, SIZE_ACK_REPORT); + // result = ack.checkSize(); + // if (result != returnvalue::OK) { + // return result; + // } + // + // result = ack.checkCrc(); + // if (result != returnvalue::OK) { + // 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); + // 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; + // } + // } return result; } @@ -987,38 +987,39 @@ 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; - } - - result = exe.checkCrc(); - if (result != returnvalue::OK) { - sif::error << "PlocSupervisorHandler::handleExecutionReport: CRC failure" << std::endl; - 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; - } - } - nextReplyId = supv::NONE; + // TODO: Fix + // ExecutionReport exe(data, SIZE_EXE_REPORT); + // result = exe.checkSize(); + // if (result != returnvalue::OK) { + // return result; + // } + // + // result = exe.checkCrc(); + // if (result != returnvalue::OK) { + // sif::error << "PlocSupervisorHandler::handleExecutionReport: CRC failure" << std::endl; + // 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; + // } + // } + // nextReplyId = supv::NONE; return result; } @@ -2107,33 +2108,36 @@ ReturnValue_t PlocSupervisorHandler::handleExecutionSuccessReport(const uint8_t* DeviceCommandId_t commandId = getPendingCommand(); 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(); -#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 - sif::info << "PlocSupervisorHandler: Read GPIO TM, State: " << gpioState << std::endl; -#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ - DeviceCommandMap::iterator iter = deviceCommandMap.find(commandId); - if (iter->second.sendReplyTo == NO_COMMAND_ID) { - return returnvalue::OK; - } - uint8_t data[sizeof(gpioState)]; - size_t size = 0; - result = SerializeAdapter::serialize(&gpioState, data, &size, sizeof(gpioState), - SerializeIF::Endianness::BIG); - if (result != returnvalue::OK) { - sif::debug << "PlocSupervisorHandler: Failed to deserialize GPIO state" << std::endl; - } - result = actionHelper.reportData(iter->second.sendReplyTo, commandId, data, sizeof(data)); - if (result != returnvalue::OK) { - sif::warning << "PlocSupervisorHandler: Read GPIO, failed to report data" << std::endl; - } + // TODO: Fix + // 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(); + //#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 + // sif::info << "PlocSupervisorHandler: Read GPIO TM, State: " << gpioState << std::endl; + //#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + // DeviceCommandMap::iterator iter = deviceCommandMap.find(commandId); + // if (iter->second.sendReplyTo == NO_COMMAND_ID) { + // return returnvalue::OK; + // } + // uint8_t data[sizeof(gpioState)]; + // size_t size = 0; + // result = SerializeAdapter::serialize(&gpioState, data, &size, sizeof(gpioState), + // SerializeIF::Endianness::BIG); + // if (result != returnvalue::OK) { + // sif::debug << "PlocSupervisorHandler: Failed to deserialize GPIO state" << + // std::endl; + // } + // result = actionHelper.reportData(iter->second.sendReplyTo, commandId, data, + // sizeof(data)); if (result != returnvalue::OK) { + // sif::warning << "PlocSupervisorHandler: Read GPIO, failed to report data" << + // std::endl; + // } break; } case supv::SET_TIME_REF: { diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 604a6c5e..53488ce2 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -501,7 +501,7 @@ ReturnValue_t PlocSupvHelper::prepareUpdate() { ReturnValue_t result = returnvalue::OK; resetSpParams(); supv::NoPayloadPacket packet(spParams, Apids::BOOT_MAN, - static_cast(BootManServiceIds::PREPARE_UPDATE)); + static_cast(tc::BootManId::PREPARE_UPDATE)); result = packet.buildPacket(); if (result != returnvalue::OK) { return result; @@ -522,7 +522,7 @@ ReturnValue_t PlocSupvHelper::eraseMemory() { if (result != returnvalue::OK) { return result; } - result = handlePacketTransmission(eraseMemory, supv::recv_timeout::ERASE_MEMORY); + result = handlePacketTransmission(eraseMemory, supv::timeout::ERASE_MEMORY); if (result != returnvalue::OK) { return result; } @@ -562,27 +562,28 @@ ReturnValue_t PlocSupvHelper::sendCommand(ploc::SpTcBase& packet) { 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; - } + // TODO: Fix + // 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; } @@ -601,22 +602,23 @@ ReturnValue_t PlocSupvHelper::handleExe(uint32_t timeout) { } 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; + // TODO: Fix + // 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 OK; } ReturnValue_t PlocSupvHelper::handleTmReception(size_t remainingBytes, uint8_t* readBuf, @@ -753,7 +755,7 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { } bool exeAlreadyHandled = false; - uint32_t timeout = std::max(CRC_EXECUTION_TIMEOUT, supv::recv_timeout::UPDATE_STATUS_REPORT); + uint32_t timeout = std::max(CRC_EXECUTION_TIMEOUT, supv::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) { @@ -762,7 +764,7 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { } 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); + supv::timeout::UPDATE_STATUS_REPORT); if (result != returnvalue::OK) { sif::warning << "PlocSupvHelper::handleCheckMemoryCommand: Failed to receive update status report" @@ -860,8 +862,8 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception(ploc::SpTmReader& reade return EVENT_BUFFER_REPLY_INVALID_APID; } // TODO: Fix -// file.write(reinterpret_cast(reader.getPacketData()), -// reader.getPayloadDataLength()); + // file.write(reinterpret_cast(reader.getPacketData()), + // reader.getPayloadDataLength()); } return result; } diff --git a/mission/devices/devicedefinitions/SpBase.h b/mission/devices/devicedefinitions/SpBase.h index 6cd4a803..f34e921a 100644 --- a/mission/devices/devicedefinitions/SpBase.h +++ b/mission/devices/devicedefinitions/SpBase.h @@ -102,7 +102,7 @@ class SpTmReader : public SpacePacketReader { return setReadOnlyData(buf, maxSize); } - ReturnValue_t checkCrc() { + ReturnValue_t checkCrc() const { if (CRC::crc16ccitt(getFullData(), getFullPacketLen()) != 0) { return returnvalue::FAILED; } From cfe7599f62787f3b7f872ec5b7a1b45303103f79 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 11:18:03 +0100 Subject: [PATCH 036/176] use result namespace instead of interface --- .../PlocSupervisorDefinitions.h | 105 +++++++++++++----- .../devicedefinitions/SupvReturnValuesIF.h | 61 ---------- linux/devices/ploc/PlocSupervisorHandler.cpp | 44 ++++---- linux/devices/ploc/PlocSupervisorHandler.h | 1 - 4 files changed, 102 insertions(+), 109 deletions(-) delete mode 100644 linux/devices/devicedefinitions/SupvReturnValuesIF.h diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index c564b6e4..aa28c143 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -10,34 +10,67 @@ #include #include -#include "linux/devices/devicedefinitions/SupvReturnValuesIF.h" #include "mission/devices/devicedefinitions/SpBase.h" using namespace returnvalue; namespace supv { -static const uint8_t CLASS_ID = CLASS_ID::PLOC_SUPERVISOR_HANDLER; +namespace result { +static const uint8_t INTERFACE_ID = CLASS_ID::SUPV_RETURN_VALUES_IF; -static constexpr ReturnValue_t CRC_MISSMATCH = makeCode(CLASS_ID, 1); -static constexpr ReturnValue_t APID_MISSMATCH = makeCode(CLASS_ID, 2); -static constexpr ReturnValue_t BUF_TOO_SMALL = makeCode(CLASS_ID, 3); +//! [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); -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; +static constexpr ReturnValue_t BUF_TOO_SMALL = MAKE_RETURN_CODE(0xC0); +}; // namespace result static constexpr uint16_t DEFAULT_SEQ_COUNT = 0; @@ -1065,15 +1098,15 @@ class VerificationReport { virtual ReturnValue_t parse() { if (not readerBase.crcIsOk()) { - return CRC_MISSMATCH; + return result::CRC_FAILURE; } if (readerBase.getApid() != Apids::TMTC_MAN) { - return APID_MISSMATCH; + return result::INVALID_APID; } if (readerBase.getBufSize() < MIN_PAYLOAD_LEN + 8) { sif::error << "VerificationReport: Invalid verification report, payload too small" << std::endl; - return BUF_TOO_SMALL; + return result::BUF_TOO_SMALL; } const uint8_t* payloadStart = readerBase.getPayloadStart(); size_t remLen = PAYLOAD_LEN; @@ -1119,7 +1152,7 @@ class VerificationReport { virtual ReturnValue_t checkApid() { return returnvalue::FAILED; } - private: + protected: TmBase& readerBase; uint8_t refApid = 0; uint8_t refServiceId = 0; @@ -1209,6 +1242,10 @@ class ExecutionReport : public VerificationReport { ExecutionReport(TmBase& readerBase) : VerificationReport(readerBase) {} ReturnValue_t parse() override { + if (readerBase.getServiceId() == static_cast(tm::TmtcId::EXEC_NAK)) { + printStatusInformation(); + return result::RECEIVED_EXE_FAILURE; + } /* uint16_t apid = this->getApid(); if (apid == APID_EXE_SUCCESS) { return returnvalue::OK; @@ -1660,7 +1697,7 @@ class UpdateStatusReport : public ploc::SpTmReader { ReturnValue_t verifycrc(uint16_t goodCrc) const { if (crc != goodCrc) { - return SupvReturnValuesIF::UPDATE_CRC_FAILURE; + return result::UPDATE_CRC_FAILURE; } return returnvalue::OK; } @@ -1681,7 +1718,7 @@ class UpdateStatusReport : public ploc::SpTmReader { ReturnValue_t lengthCheck() { if (getFullPacketLen() != FULL_SIZE) { - return SupvReturnValuesIF::UPDATE_STATUS_REPORT_INVALID_LENGTH; + return result::UPDATE_STATUS_REPORT_INVALID_LENGTH; } return returnvalue::OK; } @@ -2020,6 +2057,22 @@ class RequestLoggingData : public TcBase { 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 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/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index f26012a7..6ec92f98 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -14,6 +14,8 @@ #include "fsfw/ipc/QueueFactory.h" #include "fsfw/timemanager/Clock.h" +using namespace supv; + PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie, Gpio uartIsolatorSwitch, power::Switch_t powerSwitch, @@ -103,7 +105,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, } if (plocSupvHelperExecuting) { - return SupvReturnValuesIF::SUPV_HELPER_EXECUTING; + return result::SUPV_HELPER_EXECUTING; } result = acceptExternalDeviceCommands(); @@ -114,7 +116,7 @@ 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; } UpdateParams params; result = extractUpdateCommand(data, size, params); @@ -148,7 +150,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, } case LOGGING_REQUEST_EVENT_BUFFERS: { if (size > config::MAX_PATH_SIZE) { - return SupvReturnValuesIF::FILENAME_TOO_LONG; + return result::FILENAME_TOO_LONG; } result = supvHelper->startEventBufferRequest( std::string(reinterpret_cast(data), size)); @@ -704,7 +706,7 @@ ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t r default: { sif::debug << "PlocSupervisorHandler::scanForReply: Reply has invalid apid" << std::endl; *foundLen = remainingSize; - return SupvReturnValuesIF::INVALID_APID; + return result::INVALID_APID; } } @@ -920,7 +922,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; } @@ -1028,7 +1030,7 @@ 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; } @@ -1104,7 +1106,7 @@ ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data) result = verifyPacket(data, supv::SIZE_BOOT_STATUS_REPORT); - if (result == SupvReturnValuesIF::CRC_FAILURE) { + if (result == result::CRC_FAILURE) { sif::error << "PlocSupervisorHandler::handleBootStatusReport: Boot status report has invalid" " crc" << std::endl; @@ -1170,7 +1172,7 @@ ReturnValue_t PlocSupervisorHandler::handleLatchupStatusReport(const uint8_t* da result = verifyPacket(data, supv::SIZE_LATCHUP_STATUS_REPORT); - if (result == SupvReturnValuesIF::CRC_FAILURE) { + if (result == result::CRC_FAILURE) { sif::error << "PlocSupervisorHandler::handleLatchupStatusReport: Latchup status report has " << "invalid crc" << std::endl; return result; @@ -1290,7 +1292,7 @@ ReturnValue_t PlocSupervisorHandler::handleAdcReport(const uint8_t* data) { 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; @@ -1446,7 +1448,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); @@ -1495,7 +1497,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): { @@ -1533,7 +1535,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); @@ -1585,7 +1587,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); @@ -1831,7 +1833,7 @@ ReturnValue_t PlocSupervisorHandler::parseMramPackets(const uint8_t* packet, siz sif::info << "PlocSupervisorHandler::parseMramPackets: Can not find MRAM packet in space " "packet buffer" << std::endl; - return SupvReturnValuesIF::MRAM_PACKET_PARSING_FAILURE; + return result::MRAM_PACKET_PARSING_FAILURE; } } @@ -1917,7 +1919,7 @@ void PlocSupervisorHandler::increaseExpectedMramReplies(DeviceCommandId_t id) { 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 result::NO_MRAM_PACKET; } return APERIODIC_REPLY; } @@ -1943,7 +1945,7 @@ 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 + ccsds::HEADER_LEN), packetLen - 1); @@ -1979,7 +1981,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 @@ -1995,7 +1997,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) + "-" + @@ -2010,7 +2012,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); @@ -2059,7 +2061,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); @@ -2158,7 +2160,7 @@ void PlocSupervisorHandler::handleExecutionFailureReport(uint16_t statusCode) { if (commandId != DeviceHandlerIF::NO_COMMAND_ID) { triggerEvent(SUPV_EXE_FAILURE, commandId, static_cast(statusCode)); } - sendFailureReport(EXE_REPORT, SupvReturnValuesIF::RECEIVED_EXE_FAILURE); + sendFailureReport(EXE_REPORT, result::RECEIVED_EXE_FAILURE); disableExeReportReply(); } diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 21ae743d..744d05ea 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -12,7 +12,6 @@ #include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" #include "fsfw_hal/linux/uart/UartComIF.h" #include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" -#include "linux/devices/devicedefinitions/SupvReturnValuesIF.h" /** * @brief This is the device handler for the supervisor of the PLOC which is programmed by From 9d02322cd733aa2e9d21fce3ba90754c860c47f9 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 14:26:52 +0100 Subject: [PATCH 037/176] continue refactoring --- .../PlocSupervisorDefinitions.h | 76 ++-- linux/devices/ploc/PlocSupervisorHandler.cpp | 328 +++++++++--------- linux/devices/ploc/PlocSupervisorHandler.h | 19 +- linux/devices/ploc/PlocSupvUartMan.cpp | 242 ++++++------- 4 files changed, 347 insertions(+), 318 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index aa28c143..34ac413e 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -142,20 +142,20 @@ 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; +// 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 @@ -163,7 +163,7 @@ static const uint16_t APID_DATA_LOGGER_DATA = 0x20D; // 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; -enum Apids { +enum Apid { TMTC_MAN = 0x00, HK = 0x01, BOOT_MAN = 0x02, @@ -445,6 +445,8 @@ class TcBase : public ploc::SpTcBase { 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; @@ -507,7 +509,7 @@ class MPSoCBootSelect : public TcBase { * @note Selection of partitions is currently not supported. */ MPSoCBootSelect(TcParams params) - : TcBase(params, Apids::BOOT_MAN, static_cast(tc::BootManId::SELECT_IMAGE), 4) {} + : 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(); @@ -534,7 +536,7 @@ class SetTimeRef : public TcBase { public: static constexpr size_t PAYLOAD_LEN = 8; SetTimeRef(TcParams params) - : TcBase(params, Apids::TMTC_MAN, static_cast(tc::TmtcId::TIME_REF), 8) {} + : TcBase(params, Apid::TMTC_MAN, static_cast(tc::TmtcId::TIME_REF), 8) {} ReturnValue_t buildPacket(Clock::TimeOfDay_t* time) { auto res = checkSizeAndSerializeHeader(); @@ -609,7 +611,7 @@ class SetBootTimeout : public TcBase { * @param timeout The boot timeout in milliseconds. */ SetBootTimeout(TcParams params) - : TcBase(params, Apids::BOOT_MAN, static_cast(tc::BootManId::SET_BOOT_TIMEOUT), + : TcBase(params, Apid::BOOT_MAN, static_cast(tc::BootManId::SET_BOOT_TIMEOUT), PAYLOAD_LEN) {} ReturnValue_t buildPacket(uint32_t timeout) { @@ -641,7 +643,7 @@ class SetRestartTries : public TcBase { * @param restartTries Maximum restart tries to set. */ SetRestartTries(TcParams params) - : TcBase(params, Apids::BOOT_MAN, static_cast(tc::BootManId::SET_MAX_REBOOT_TRIES), + : TcBase(params, Apid::BOOT_MAN, static_cast(tc::BootManId::SET_MAX_REBOOT_TRIES), 1) {} ReturnValue_t buildPacket(uint8_t restartTries) { @@ -670,7 +672,7 @@ class DisablePeriodicHkTransmission : public TcBase { * @brief Constructor */ DisablePeriodicHkTransmission(TcParams params) - : TcBase(params, Apids::HK, static_cast(tc::HkId::ENABLE), 1) {} + : TcBase(params, Apid::HK, static_cast(tc::HkId::ENABLE), 1) {} ReturnValue_t buildPacket() { auto res = checkSizeAndSerializeHeader(); @@ -699,7 +701,7 @@ class LatchupAlert : public TcBase { * @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(TcParams params) : TcBase(params, Apids::LATCHUP_MON) { setLenFromPayloadLen(1); } + LatchupAlert(TcParams params) : TcBase(params, Apid::LATCHUP_MON) { setLenFromPayloadLen(1); } ReturnValue_t buildPacket(bool state, uint8_t latchupId) { if (state) { @@ -731,7 +733,7 @@ class SetAlertlimit : public TcBase { * @param dutycycle */ SetAlertlimit(TcParams params) - : TcBase(params, Apids::LATCHUP_MON, static_cast(tc::LatchupMonId::SET_ALERT_LIMIT), + : TcBase(params, Apid::LATCHUP_MON, static_cast(tc::LatchupMonId::SET_ALERT_LIMIT), 5) {} ReturnValue_t buildPacket(uint8_t latchupId, uint32_t dutycycle) { @@ -771,7 +773,7 @@ class SetAdcWindowAndStride : public TcBase { * @param stridingStepSize */ SetAdcWindowAndStride(TcParams params) - : TcBase(params, Apids::ADC_MON, static_cast(tc::AdcMonId::SET_WINDOW_STRIDE), 4) {} + : 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(); @@ -804,7 +806,7 @@ class SetAdcThreshold : public TcBase { * @param threshold */ SetAdcThreshold(TcParams params) - : TcBase(params, Apids::ADC_MON, static_cast(tc::AdcMonId::SET_ADC_THRESHOLD), 4) {} + : TcBase(params, Apid::ADC_MON, static_cast(tc::AdcMonId::SET_ADC_THRESHOLD), 4) {} ReturnValue_t buildPacket(uint32_t threshold) { auto res = checkSizeAndSerializeHeader(); @@ -834,7 +836,7 @@ class RunAutoEmTests : public TcBase { * @param test 1 - complete EM test, 2 - Short test (only memory readback NVM0,1,3) */ RunAutoEmTests(TcParams params) - : TcBase(params, Apids::TMTC_MAN, static_cast(tc::TmtcId::RUN_AUTO_EM_TEST), 1) {} + : TcBase(params, Apid::TMTC_MAN, static_cast(tc::TmtcId::RUN_AUTO_EM_TEST), 1) {} ReturnValue_t buildPacket(uint8_t test) { auto res = checkSizeAndSerializeHeader(); @@ -865,7 +867,7 @@ class SetGpio : public TcBase { * @param val */ SetGpio(TcParams params) - : TcBase(params, Apids::TMTC_MAN, static_cast(tc::TmtcId::SET_GPIO), 3) {} + : 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(); @@ -901,7 +903,7 @@ class ReadGpio : public TcBase { * @param pin */ ReadGpio(TcParams params) - : TcBase(params, Apids::TMTC_MAN, static_cast(tc::TmtcId::READ_GPIO), 2) {} + : TcBase(params, Apid::TMTC_MAN, static_cast(tc::TmtcId::READ_GPIO), 2) {} ReturnValue_t buildPacket(uint8_t port, uint8_t pin) { auto res = checkSizeAndSerializeHeader(); @@ -925,7 +927,7 @@ class ReadGpio : public TcBase { class SetShutdownTimeout : public TcBase { public: SetShutdownTimeout(TcParams params) - : TcBase(params, Apids::BOOT_MAN, static_cast(tc::BootManId::SHUTDOWN_TIMEOUT), 4) {} + : TcBase(params, Apid::BOOT_MAN, static_cast(tc::BootManId::SHUTDOWN_TIMEOUT), 4) {} ReturnValue_t buildPacket(uint32_t timeout) { auto res = checkSizeAndSerializeHeader(); @@ -957,7 +959,7 @@ class CheckMemory : public TcBase { * @param length Length in bytes of memory region */ CheckMemory(TcParams params) - : TcBase(params, Apids::MEM_MAN, static_cast(tc::MemManId::CHECK), 10) {} + : 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(); @@ -997,7 +999,7 @@ class WriteMemory : public TcBase { * @param updateData Pointer to buffer containing update data */ WriteMemory(TcParams params) - : TcBase(params, Apids::MEM_MAN, static_cast(tc::MemManId::WRITE), 1) {} + : 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) { @@ -1060,7 +1062,7 @@ class WriteMemory : public TcBase { class EraseMemory : public TcBase { public: EraseMemory(TcParams params) - : TcBase(params, Apids::MEM_MAN, static_cast(tc::MemManId::ERASE), PAYLOAD_LENGTH) {} + : 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(); @@ -1100,7 +1102,7 @@ class VerificationReport { if (not readerBase.crcIsOk()) { return result::CRC_FAILURE; } - if (readerBase.getApid() != Apids::TMTC_MAN) { + if (readerBase.getApid() != Apid::TMTC_MAN) { return result::INVALID_APID; } if (readerBase.getBufSize() < MIN_PAYLOAD_LEN + 8) { @@ -1823,7 +1825,7 @@ class FactoryReset : public TcBase { * * @param op */ - FactoryReset(TcParams params) : TcBase(params, Apids::TMTC_MAN, 0x11, 1) {} + FactoryReset(TcParams params) : TcBase(params, Apid::TMTC_MAN, 0x11, 1) {} ReturnValue_t buildPacket(Op op) { auto res = checkSizeAndSerializeHeader(); @@ -1867,7 +1869,7 @@ class EnableNvms : public TcBase { * @param bp1 Partition pin 1 * @param bp2 Partition pin 2 */ - EnableNvms(TcParams params) : TcBase(params, Apids::TMTC_MAN, 0x06, 2) {} + EnableNvms(TcParams params) : TcBase(params, Apid::TMTC_MAN, 0x06, 2) {} ReturnValue_t buildPacket(uint8_t nvm01, uint8_t nvm3) { auto res = checkSizeAndSerializeHeader(); @@ -1901,7 +1903,7 @@ class MramCmd : public TcBase { * * @note The content at the stop address is excluded from the dump or wipe operation. */ - MramCmd(TcParams params) : TcBase(params, Apids::DATA_LOGGER) { setLenFromPayloadLen(6); } + 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) { @@ -1996,8 +1998,8 @@ class SetAdcEnabledChannels : public TcBase { * @param ch Defines channels to be enabled or disabled. */ SetAdcEnabledChannels(TcParams params) - : TcBase(params, Apids::ADC_MON, static_cast(tc::AdcMonId::SET_ENABLED_CHANNELS), - 2) {} + : TcBase(params, Apid::ADC_MON, static_cast(tc::AdcMonId::SET_ENABLED_CHANNELS), 2) { + } ReturnValue_t buildPacket(uint16_t ch) { auto res = checkSizeAndSerializeHeader(); diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 6ec92f98..9f9ac9ea 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -223,17 +223,17 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d spParams.buf = commandBuffer; switch (deviceCommand) { case GET_HK_REPORT: { - prepareEmptyCmd(Apids::HK, static_cast(tc::HkId::GET_REPORT)); + prepareEmptyCmd(Apid::HK, static_cast(tc::HkId::GET_REPORT)); result = returnvalue::OK; break; } case START_MPSOC: { - prepareEmptyCmd(Apids::BOOT_MAN, static_cast(tc::BootManId::START_MPSOC)); + prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::START_MPSOC)); result = returnvalue::OK; break; } case SHUTDOWN_MPSOC: { - prepareEmptyCmd(Apids::BOOT_MAN, static_cast(tc::BootManId::SHUTDOWN_MPSOC)); + prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::SHUTDOWN_MPSOC)); result = returnvalue::OK; break; } @@ -243,7 +243,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case RESET_MPSOC: { - prepareEmptyCmd(Apids::BOOT_MAN, static_cast(tc::BootManId::RESET_MPSOC)); + prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::RESET_MPSOC)); result = returnvalue::OK; break; } @@ -267,7 +267,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case GET_BOOT_STATUS_REPORT: { - prepareEmptyCmd(Apids::BOOT_MAN, static_cast(tc::BootManId::GET_BOOT_STATUS_REPORT)); + prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::GET_BOOT_STATUS_REPORT)); result = returnvalue::OK; break; } @@ -299,8 +299,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d // break; // } case GET_LATCHUP_STATUS_REPORT: { - prepareEmptyCmd(Apids::LATCHUP_MON, - static_cast(tc::LatchupMonId::GET_STATUS_REPORT)); + prepareEmptyCmd(Apid::LATCHUP_MON, static_cast(tc::LatchupMonId::GET_STATUS_REPORT)); result = returnvalue::OK; break; } @@ -381,7 +380,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case FACTORY_FLASH: { - prepareEmptyCmd(Apids::BOOT_MAN, static_cast(tc::BootManId::FACTORY_FLASH)); + prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::FACTORY_FLASH)); result = returnvalue::OK; break; } @@ -435,7 +434,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d // break; // } case RESET_PL: { - prepareEmptyCmd(Apids::BOOT_MAN, static_cast(tc::BootManId::RESET_PL)); + prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::RESET_PL)); result = returnvalue::OK; break; } @@ -654,73 +653,66 @@ 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); + uint16_t apid = tmReader.getApid(); //(*(start) << 8 | *(start + 1)) & APID_MASK; 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 = SIZE_ACK_REPORT; + *foundId = ACK_REPORT; + return OK; + } + case (static_cast(supv::tm::TmtcId::EXEC_ACK)): + case (static_cast(supv::tm::TmtcId::EXEC_NAK)): { + *foundLen = SIZE_EXE_REPORT; + *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 = SIZE_HK_REPORT; + *foundId = 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 = SIZE_BOOT_STATUS_REPORT; + *foundId = 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 result::INVALID_APID; + } + case (Apid::MEM_MAN): { + if (tmReader.getServiceId() == + static_cast(supv::tm::MemManId::UPDATE_STATUS_REPORT)) { + // TODO: I think this will be handled by the uart manager + } } } - - 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, @@ -771,6 +763,16 @@ ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id, 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; +} + void PlocSupervisorHandler::setNormalDatapoolEntriesInvalid() {} uint32_t PlocSupervisorHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { @@ -932,56 +934,57 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) { ReturnValue_t result = returnvalue::OK; // TODO: Fix - // AcknowledgmentReport ack(data, SIZE_ACK_REPORT); - // result = ack.checkSize(); - // if (result != returnvalue::OK) { - // return result; - // } + + // AcknowledgmentReport ack(data, SIZE_ACK_REPORT); + // result = ack.checkSize(); + // if (result != returnvalue::OK) { + // return result; + // } // - // result = ack.checkCrc(); - // if (result != returnvalue::OK) { - // 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); - // disableAllReplies(); - // return returnvalue::OK; - // } + // result = ack.checkCrc(); + // if (result != returnvalue::OK) { + // 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); + // disableAllReplies(); + // return returnvalue::OK; + // } // - // result = ack.checkApid(); + // 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; - // } - // } + // 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; + // } + // } return result; } @@ -1806,39 +1809,40 @@ 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 >= 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::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::handleMramDumpPacket(DeviceCommandId_t id) { ReturnValue_t result = returnvalue::FAILED; @@ -1916,13 +1920,14 @@ 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 result::NO_MRAM_PACKET; - } - return APERIODIC_REPLY; -} +// 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::handleMramDumpFile(DeviceCommandId_t id) { #ifdef XIPHOS_Q7S @@ -2164,6 +2169,19 @@ void PlocSupervisorHandler::handleExecutionFailureReport(uint16_t statusCode) { disableExeReportReply(); } +void PlocSupervisorHandler::handleBadApidServiceCombination(Event event, unsigned int apid, + unsigned int serviceId) { + const char* printString = ""; + if (event == SUPV_UNKNOWN_TM) { + printString = "Unknown"; + } else if (event == SUPV_UNINIMPLEMENTED_TM) { + printString = "Unimplemented"; + } + triggerEvent(event, apid, tmReader.getServiceId()); + sif::error << printString << " APID service combination 0x" << std::setw(2) << std::setfill('0') + << std::hex << apid << ", " << 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; diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 744d05ea..4221bf4d 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -64,18 +64,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_SHUWDOWN_BUILD_FAILED = MAKE_EVENT(8, severity::LOW); static const uint16_t APID_MASK = 0x7FF; static const uint16_t PACKET_SEQUENCE_COUNT_MASK = 0x3FFF; @@ -121,6 +124,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { supv::AdcReport adcReport; const power::Switch_t powerSwitch = power::NO_SWITCH; + supv::TmBase tmReader; PlocSupvHelper* supvHelper = nullptr; MessageQueueIF* eventQueue = nullptr; @@ -210,6 +214,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t handleBootStatusReport(const uint8_t* data); ReturnValue_t handleLatchupStatusReport(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); @@ -317,7 +322,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 +340,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 diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 53488ce2..997c6a7a 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -500,7 +500,7 @@ ReturnValue_t PlocSupvHelper::selectMemory() { ReturnValue_t PlocSupvHelper::prepareUpdate() { ReturnValue_t result = returnvalue::OK; resetSpParams(); - supv::NoPayloadPacket packet(spParams, Apids::BOOT_MAN, + supv::NoPayloadPacket packet(spParams, Apid::BOOT_MAN, static_cast(tc::BootManId::PREPARE_UPDATE)); result = packet.buildPacket(); if (result != returnvalue::OK) { @@ -584,7 +584,7 @@ ReturnValue_t PlocSupvHelper::handleAck() { // } // return result; // } - return returnvalue::OK; + return result; } ReturnValue_t PlocSupvHelper::handleExe(uint32_t timeout) { @@ -735,74 +735,76 @@ ReturnValue_t PlocSupvHelper::calcImageCrc() { 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::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::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; - } - } + // TODO: Fix + // 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::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::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; } @@ -816,55 +818,57 @@ uint32_t PlocSupvHelper::getFileSize(std::string filename) { 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; - } - // TODO: Fix - // file.write(reinterpret_cast(reader.getPacketData()), - // reader.getPayloadDataLength()); - } + // 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; } From 763bf2d85bc9524c13cc0ef0a5fbc322b9ca6ec6 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 14:29:41 +0100 Subject: [PATCH 038/176] remove flush call, belongs in lower layer --- linux/devices/ploc/PlocSupervisorHandler.cpp | 13 ++++--------- 1 file changed, 4 insertions(+), 9 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 9f9ac9ea..df0796cc 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -448,14 +448,6 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d 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; } @@ -706,7 +698,10 @@ ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t r case (Apid::MEM_MAN): { if (tmReader.getServiceId() == static_cast(supv::tm::MemManId::UPDATE_STATUS_REPORT)) { - // TODO: I think this will be handled by the uart manager + // TODO: I think this will be handled by the uart manager? + // Actually, this is a bit tricky. Maybe the lower level will have two separate ring + // buffers, one for internally handled packets and one for packets which are handled + // here? } } } From f564fb5c1af297d40077f0341412cb065d886dfe Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 14:52:07 +0100 Subject: [PATCH 039/176] some fixes for thread shutdown code --- linux/devices/ploc/PlocSupervisorHandler.cpp | 28 ++-- linux/devices/ploc/PlocSupvUartMan.cpp | 137 +++++++++++-------- linux/devices/ploc/PlocSupvUartMan.h | 13 +- 3 files changed, 102 insertions(+), 76 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index df0796cc..f71cafe3 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -64,7 +64,7 @@ ReturnValue_t PlocSupervisorHandler::initialize() { if (result != returnvalue::OK) { return ObjectManagerIF::CHILD_INIT_FAILED; } - supvHelper->setComCookie(comCookie); + // supvHelper->setComCookie(comCookie); result = eventSubscription(); if (result != returnvalue::OK) { @@ -97,7 +97,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, switch (actionId) { case TERMINATE_SUPV_HELPER: { - supvHelper->stopProcess(); + supvHelper->stop(); return EXECUTION_FINISHED; } default: @@ -148,18 +148,18 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, plocSupvHelperExecuting = true; return EXECUTION_FINISHED; } - case LOGGING_REQUEST_EVENT_BUFFERS: { - if (size > config::MAX_PATH_SIZE) { - return result::FILENAME_TOO_LONG; - } - result = supvHelper->startEventBufferRequest( - std::string(reinterpret_cast(data), size)); - if (result != returnvalue::OK) { - return result; - } - plocSupvHelperExecuting = true; - return EXECUTION_FINISHED; - } + // case LOGGING_REQUEST_EVENT_BUFFERS: { + // if (size > config::MAX_PATH_SIZE) { + // return result::FILENAME_TOO_LONG; + // } + // result = supvHelper->startEventBufferRequest( + // std::string(reinterpret_cast(data), size)); + // if (result != returnvalue::OK) { + // return result; + // } + // plocSupvHelperExecuting = true; + // return EXECUTION_FINISHED; + // } default: break; } diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 997c6a7a..c9e9ad72 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -167,7 +167,7 @@ ReturnValue_t PlocSupvHelper::setComIF(UartComIF* uartComIF_) { return returnvalue::OK; } -void PlocSupvHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; } +// void PlocSupvHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; } ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId, uint32_t startAddress) { @@ -182,6 +182,12 @@ ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId, } ReturnValue_t PlocSupvHelper::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); @@ -204,70 +210,93 @@ ReturnValue_t PlocSupvHelper::performUpdate(const supv::UpdateParams& params) { 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; + { + 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::LONGER_REQUEST; + request = Request::UPDATE; } - 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; - request = Request::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); + 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 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; - request = Request::CHECK_MEMORY; - uartComIF->flushUartTxAndRxBuf(comCookie); - semaphore->release(); +ReturnValue_t PlocSupvHelper::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::LONGER_REQUEST; + request = Request::CHECK_MEMORY; + update.memoryId = memoryId; + update.startAddress = startAddress; + update.length = sizeToCheck; + update.crcShouldBeChecked = checkCrc; + } return returnvalue::OK; } -void PlocSupvHelper::initiateUpdateContinuation() { +ReturnValue_t PlocSupvHelper::initiateUpdateContinuation() { + lock->lockMutex(); + InternalState current = state; + lock->unlockMutex(); + if (current != InternalState::DEFAULT) { + return HasActionsIF::IS_BUSY; + } + MutexGuard mg(lock); + state = InternalState::LONGER_REQUEST; request = Request::CONTINUE_UPDATE; - semaphore->release(); -} - -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 PlocSupvHelper::stopProcess() { terminate = true; } +// 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 PlocSupvHelper::stop() { + MutexGuard mg(lock); + state = InternalState::GO_TO_SLEEP; +} void PlocSupvHelper::executeFullCheckMemoryCommand() { ReturnValue_t result; @@ -356,11 +385,6 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { 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) { @@ -1031,5 +1055,8 @@ ReturnValue_t PlocSupvHelper::parseRecRingBufForHdlc(size_t& readSize) { void PlocSupvHelper::performUartShutdown() { tcflush(serialPort, TCIOFLUSH); + // Clear ring buffers + recRingBuf.clear(); + ipcRingBuf.clear(); state = InternalState::GO_TO_SLEEP; } diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index d36234e2..9426b2e4 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -122,7 +122,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, ReturnValue_t performOperation(uint8_t operationCode = 0) override; ReturnValue_t setComIF(UartComIF* uartComfIF_); - void setComCookie(CookieIF* comCookie_); + // void setComCookie(CookieIF* comCookie_); /** * @brief Starts update procedure @@ -136,24 +136,24 @@ class PlocSupvHelper : public DeviceCommunicationIF, 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 startEventBufferRequest(std::string path); + // ReturnValue_t startEventBufferRequest(std::string path); /** * @brief Can be used to interrupt a running data transfer. */ - void stopProcess(); + void stop(); static uint32_t buildProgParams1(uint8_t percent, uint16_t seqCount); @@ -242,7 +242,6 @@ class PlocSupvHelper : public DeviceCommunicationIF, std::array tmBuf{}; - bool terminate = false; bool debugMode = false; /** * Communication interface responsible for data transactions between OBC and Supervisor. From 28cd78db96ba6999d4b1376bb35fe2336d851073 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 16:26:30 +0100 Subject: [PATCH 040/176] implemented the last tricky parts --- .../PlocSupervisorDefinitions.h | 151 ++++---- linux/devices/ploc/PlocSupervisorHandler.cpp | 10 +- linux/devices/ploc/PlocSupvUartMan.cpp | 364 ++++++++++-------- linux/devices/ploc/PlocSupvUartMan.h | 34 +- mission/devices/devicedefinitions/SpBase.h | 2 + 5 files changed, 297 insertions(+), 264 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 34ac413e..2b248404 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -70,6 +70,8 @@ static const ReturnValue_t UPDATE_CRC_FAILURE = MAKE_RETURN_CODE(0xB2); static const ReturnValue_t SUPV_HELPER_EXECUTING = MAKE_RETURN_CODE(0xB3); 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; @@ -270,6 +272,7 @@ 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; @@ -421,6 +424,8 @@ class TcBase : public ploc::SpTcBase { payloadStart[supv::PAYLOAD_OFFSET] = id; } + uint8_t getServiceId() const { return payloadStart[supv::PAYLOAD_OFFSET]; } + static size_t fullSpDataLenFromPayloadLen(size_t payloadLen) { return SECONDARY_HEADER_LEN + payloadLen + CRC_LEN; } @@ -1168,19 +1173,11 @@ class AcknowledgmentReport : public VerificationReport { AcknowledgmentReport(TmBase& readerBase) : VerificationReport(readerBase) {} virtual ReturnValue_t parse() override { - // if (readerBase.getServiceId() != ) - // 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; - // } - return OK; + if (readerBase.getServiceId() != static_cast(tm::TmtcId::ACK) and + readerBase.getServiceId() != static_cast(tm::TmtcId::NAK)) { + return returnvalue::FAILED; + } + return VerificationReport::parse(); } void printStatusInformation() { @@ -1244,78 +1241,12 @@ class ExecutionReport : public VerificationReport { ExecutionReport(TmBase& readerBase) : VerificationReport(readerBase) {} ReturnValue_t parse() override { - if (readerBase.getServiceId() == static_cast(tm::TmtcId::EXEC_NAK)) { - printStatusInformation(); - return result::RECEIVED_EXE_FAILURE; + if (readerBase.getServiceId() != static_cast(tm::TmtcId::EXEC_ACK) and + readerBase.getServiceId() != static_cast(tm::TmtcId::EXEC_NAK)) { + return returnvalue::FAILED; } - /* 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; - }*/ - return OK; + return VerificationReport::parse(); } - - private: - static constexpr char STATUS_PRINTOUT_PREFIX[] = "Supervisor execution failure report 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 - }; - void printStatusInformation() { StatusCode statusCode = static_cast(getStatusCode()); switch (statusCode) { @@ -1520,6 +1451,60 @@ class ExecutionReport : public VerificationReport { break; } } + + private: + static constexpr char STATUS_PRINTOUT_PREFIX[] = "Supervisor execution failure report 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 + }; }; /** diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index f71cafe3..f0e56347 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -60,11 +60,11 @@ ReturnValue_t PlocSupervisorHandler::initialize() { 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 = supvHelper->setComIF(uartComIf); + // if (result != returnvalue::OK) { + // return ObjectManagerIF::CHILD_INIT_FAILED; + // } + // supvHelper->setComCookie(comCookie); result = eventSubscription(); if (result != returnvalue::OK) { diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index c9e9ad72..ef571c11 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -29,12 +29,13 @@ using namespace supv; PlocSupvHelper::PlocSupvHelper(object_id_t objectId) : SystemObject(objectId), recRingBuf(4096, true), + decodedRingBuf(1200 * MAX_STORED_DECODED_PACKETS, true), ipcRingBuf(1200 * MAX_STORED_DECODED_PACKETS, true) { - spParams.maxSize = sizeof(commandBuffer); resetSpParams(); semaphore = SemaphoreFactory::instance()->createBinarySemaphore(); semaphore->acquire(); lock = MutexFactory::instance()->createMutex(); + ipcLock = MutexFactory::instance()->createMutex(); } PlocSupvHelper::~PlocSupvHelper() = default; @@ -158,14 +159,14 @@ bool PlocSupvHelper::handleUartReception() { return false; } -ReturnValue_t PlocSupvHelper::setComIF(UartComIF* uartComIF_) { - if (uartComIF_ == nullptr) { - sif::warning << "PlocSupvHelper::initialize: Provided invalid uart com if" << std::endl; - return returnvalue::FAILED; - } - uartComIF = uartComIF_; - return returnvalue::OK; -} +// ReturnValue_t PlocSupvHelper::setComIF(UartComIF* 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_; } @@ -431,7 +432,8 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { update.bytesWritten); return result; } - result = handlePacketTransmission(packet); + // TODO: Fix + // result = handlePacketTransmission(packet); if (result != returnvalue::OK) { triggerEvent(WRITE_MEMORY_FAILED, buildProgParams1(progPercent, update.sequenceCount), update.bytesWritten); @@ -514,7 +516,7 @@ ReturnValue_t PlocSupvHelper::selectMemory() { if (result != returnvalue::OK) { return result; } - result = handlePacketTransmission(packet); + result = handlePacketTransmissionNoReply(packet); if (result != returnvalue::OK) { return result; } @@ -530,7 +532,7 @@ ReturnValue_t PlocSupvHelper::prepareUpdate() { if (result != returnvalue::OK) { return result; } - result = handlePacketTransmission(packet, PREPARE_UPDATE_EXECUTION_REPORT); + result = handlePacketTransmissionNoReply(packet, PREPARE_UPDATE_EXECUTION_REPORT); if (result != returnvalue::OK) { return result; } @@ -546,140 +548,131 @@ ReturnValue_t PlocSupvHelper::eraseMemory() { if (result != returnvalue::OK) { return result; } - result = handlePacketTransmission(eraseMemory, supv::timeout::ERASE_MEMORY); + result = handlePacketTransmissionNoReply(eraseMemory, supv::timeout::ERASE_MEMORY); if (result != returnvalue::OK) { return result; } return returnvalue::OK; } -ReturnValue_t PlocSupvHelper::handlePacketTransmission(ploc::SpTcBase& packet, - uint32_t timeoutExecutionReport) { +ReturnValue_t PlocSupvHelper::handlePacketTransmissionNoReply(supv::TcBase& packet, + uint32_t timeoutExecutionReport) { ReturnValue_t result = returnvalue::OK; - result = sendCommand(packet); + result = encodeAndSendPacket(packet.getFullPacket(), packet.getFullPacketLen()); if (result != returnvalue::OK) { return result; } - result = handleAck(); - if (result != returnvalue::OK) { - return result; - } - result = handleExe(timeoutExecutionReport); - if (result != returnvalue::OK) { - return result; + Countdown countdown(timeoutExecutionReport); + bool ackReceived = false; + while (true) { + if (not decodedQueue.empty()) { + size_t packetLen = 0; + decodedQueue.retrieve(&packetLen); + decodedRingBuf.readData(decodedBuf.data(), packetLen); + tmReader.setData(decodedBuf.data(), packetLen); + result = checkReceivedTm(); + if (result != returnvalue::OK) { + continue; + } + if (tmReader.getApid() == Apid::TMTC_MAN) { + uint8_t serviceId = tmReader.getServiceId(); + int retval = 0; + if (not ackReceived) { + retval = handleAckReception(packet, serviceId, packetLen); + if (retval == 1) { + ackReceived = true; + } else if (retval == -1) { + return returnvalue::FAILED; + } + } else { + retval = handleExeAckReception(packet, serviceId, packetLen); + if (retval == 1) { + break; + } else if (retval == -1) { + return returnvalue::FAILED; + } + } + } else { + pushIpcData(decodedBuf.data(), packetLen); + decodedRingBuf.deleteData(packetLen); + } + } else { + TaskFactory::delayTask(50); + } + if (countdown.hasTimedOut()) { + return result::NO_REPLY_TIMEOUT; + } } 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(state)); - return result; - } - return result; -} - -ReturnValue_t PlocSupvHelper::handleAck() { - ReturnValue_t result = returnvalue::OK; - - // TODO: Fix - // 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 result; -} - -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() { - // TODO: Fix - // 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 OK; -} - -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); +int PlocSupvHelper::handleAckReception(supv::TcBase& tc, uint8_t serviceId, size_t packetLen) { + 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) { - return result; + triggerEvent(ACK_RECEPTION_FAILURE); + return returnvalue::FAILED; } - readBytes += currentBytes; - remainingBytes = remainingBytes - currentBytes; - if (remainingBytes == 0) { - break; + if (ackReport.getRefApid() == tc.getApid() 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.getRefApid(), ackReport.getRefServiceId()), + ackReport.getStatusCode()); + return -1; + } + // Should never happen + return -1; + } else { + pushIpcData(decodedBuf.data(), packetLen); + decodedRingBuf.deleteData(packetLen); } } - if (remainingBytes != 0) { - sif::warning << "PlocSupvHelper::handleTmReception: Failed to read " << std::dec - << remainingBytes << " remaining bytes" << std::endl; - return returnvalue::FAILED; - } - return result; + return 0; } -ReturnValue_t PlocSupvHelper::checkReceivedTm(ploc::SpTmReader& reader) { - ReturnValue_t result = reader.checkSize(); +int PlocSupvHelper::handleExeAckReception(supv::TcBase& tc, uint8_t serviceId, size_t packetLen) { + 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 returnvalue::FAILED; + } + if (exeReport.getRefApid() == tc.getApid() 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.getRefApid(), exeReport.getRefServiceId()), + exeReport.getStatusCode()); + return -1; + } + // Should never happen + return -1; + } else { + pushIpcData(decodedBuf.data(), packetLen); + decodedRingBuf.deleteData(packetLen); + } + } + return 0; +} + +ReturnValue_t PlocSupvHelper::checkReceivedTm() { + ReturnValue_t result = tmReader.checkSize(); if (result != returnvalue::OK) { triggerEvent(SUPV_REPLY_SIZE_MISSMATCH, rememberApid); return result; } - result = reader.checkCrc(); + result = tmReader.checkCrc(); if (result != returnvalue::OK) { triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); return result; @@ -687,30 +680,6 @@ ReturnValue_t PlocSupvHelper::checkReceivedTm(ploc::SpTmReader& reader) { 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(state))); - 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(state)); - 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) { @@ -760,20 +729,64 @@ ReturnValue_t PlocSupvHelper::calcImageCrc() { ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { ReturnValue_t result = returnvalue::OK; // TODO: Fix - // resetSpParams(); - // // Will hold status report for later processing + 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; - // } + // 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 = encodeAndSendPacket(packet.getFullPacket(), packet.getFullPacketLen()); + if (result != returnvalue::OK) { + return result; + } + Countdown countdown(timeout::CRC_EXECUTION_TIMEOUT); + bool ackReceived = false; + bool checkReplyReceived = false; + while (true) { + if (not decodedQueue.empty()) { + size_t packetLen = 0; + decodedQueue.retrieve(&packetLen); + decodedRingBuf.readData(decodedBuf.data(), packetLen); + tmReader.setData(decodedBuf.data(), packetLen); + result = checkReceivedTm(); + if (result != returnvalue::OK) { + continue; + } + if (tmReader.getApid() == Apid::TMTC_MAN) { + uint8_t serviceId = tmReader.getServiceId(); + int retval = 0; + if (not ackReceived) { + retval = handleAckReception(packet, serviceId, packetLen); + if (retval == 1) { + ackReceived = true; + } else if (retval == -1) { + return returnvalue::FAILED; + } + } else if (not checkReplyReceived) { + // if (serviceId == ) + retval = handleExeAckReception(packet, serviceId, packetLen); + if (retval == 1) { + break; + } else if (retval == -1) { + return returnvalue::FAILED; + } + } + } else { + pushIpcData(decodedBuf.data(), packetLen); + decodedRingBuf.deleteData(packetLen); + } + } else { + TaskFactory::delayTask(50); + } + if (countdown.hasTimedOut()) { + return result::NO_REPLY_TIMEOUT; + } + } + return returnvalue::OK; // result = handleAck(); // if (result != returnvalue::OK) { // return result; @@ -896,7 +909,7 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception(ploc::SpTmReader& reade return result; } -void PlocSupvHelper::resetSpParams() { spParams.buf = commandBuffer; } +void PlocSupvHelper::resetSpParams() { spParams.buf = cmdBuf.data(); } ReturnValue_t PlocSupvHelper::sendMessage(CookieIF* cookie, const uint8_t* sendData, size_t sendLen) { @@ -968,8 +981,8 @@ ReturnValue_t PlocSupvHelper::handleRunningLongerRequest() { ReturnValue_t PlocSupvHelper::encodeAndSendPacket(const uint8_t* sendData, size_t sendLen) { size_t encodedLen = 0; - hdlc_add_framing(sendData, sendLen, sendBuf.data(), &encodedLen); - size_t bytesWritten = write(serialPort, sendBuf.data(), encodedLen); + hdlc_add_framing(sendData, sendLen, encodedSendBuf.data(), &encodedLen); + size_t bytesWritten = write(serialPort, encodedSendBuf.data(), encodedLen); if (bytesWritten != encodedLen) { sif::warning << "ScexUartReader::sendMessage: Sending ping command to solar experiment failed" << std::endl; @@ -980,7 +993,7 @@ ReturnValue_t PlocSupvHelper::encodeAndSendPacket(const uint8_t* sendData, size_ ReturnValue_t PlocSupvHelper::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) { - MutexGuard mg(lock); + MutexGuard mg(ipcLock); if (ipcQueue.empty()) { *size = 0; return OK; @@ -999,7 +1012,14 @@ ReturnValue_t PlocSupvHelper::tryHdlcParsing() { ReturnValue_t result = parseRecRingBufForHdlc(bytesRead); if (result == returnvalue::OK) { // Packet found, advance read pointer. - ipcRingBuf.writeData(decodedBuf.data(), bytesRead); + if (state == InternalState::LONGER_REQUEST) { + decodedRingBuf.writeData(decodedBuf.data(), bytesRead); + decodedQueue.insert(bytesRead); + } else { + MutexGuard mg(ipcLock); + ipcRingBuf.writeData(decodedBuf.data(), bytesRead); + ipcQueue.insert(bytesRead); + } recRingBuf.deleteData(bytesRead); } else if (result != NO_PACKET_FOUND) { sif::warning << "ScexUartReader::performOperation: Possible packet loss" << std::endl; @@ -1053,10 +1073,28 @@ ReturnValue_t PlocSupvHelper::parseRecRingBufForHdlc(size_t& readSize) { return NO_PACKET_FOUND; } +void PlocSupvHelper::pushIpcData(const uint8_t* data, size_t len) { + MutexGuard mg(ipcLock); + ipcRingBuf.writeData(data, len); + ipcQueue.insert(len); +} + +uint32_t PlocSupvHelper::buildApidServiceParam1(uint8_t apid, uint8_t serviceId) { + return (apid << 8) | serviceId; +} + void PlocSupvHelper::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; } diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index 9426b2e4..34d8bd2e 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -121,8 +121,8 @@ class PlocSupvHelper : public DeviceCommunicationIF, ReturnValue_t initialize() override; ReturnValue_t performOperation(uint8_t operationCode = 0) override; - ReturnValue_t setComIF(UartComIF* uartComfIF_); - // void setComCookie(CookieIF* comCookie_); + // ReturnValue_t setComIF(UartComIF* uartComfIF_); + // void setComCookie(CookieIF* comCookie_); /** * @brief Starts update procedure @@ -156,6 +156,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, void stop(); static uint32_t buildProgParams1(uint8_t percent, uint16_t seqCount); + static uint32_t buildApidServiceParam1(uint8_t apid, uint8_t serviceId); private: static constexpr ReturnValue_t REQUEST_DONE = returnvalue::makeCode(1, 0); @@ -171,7 +172,6 @@ class PlocSupvHelper : public DeviceCommunicationIF, 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; @@ -200,6 +200,8 @@ class PlocSupvHelper : public DeviceCommunicationIF, SemaphoreIF* semaphore; MutexIF* lock; + MutexIF* ipcLock; + supv::TmBase tmReader; int serialPort = 0; struct termios tty = {}; @@ -228,15 +230,17 @@ class PlocSupvHelper : public DeviceCommunicationIF, SdCardManager* sdcMan = nullptr; #endif SimpleRingBuffer recRingBuf; - std::array sendBuf = {}; + 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; - uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]{}; SpacePacketCreator creator; supv::TcParams spParams = supv::TcParams(creator); @@ -246,9 +250,9 @@ class PlocSupvHelper : public DeviceCommunicationIF, /** * Communication interface responsible for data transactions between OBC and Supervisor. */ - UartComIF* uartComIF = nullptr; - // Communication cookie. Must be set by the supervisor Handler - CookieIF* comCookie = nullptr; + // UartComIF* uartComIF = nullptr; + // Communication cookie. Must be set by the supervisor Handler + // CookieIF* comCookie = nullptr; bool timestamping = true; @@ -268,9 +272,12 @@ class PlocSupvHelper : public DeviceCommunicationIF, 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); + ReturnValue_t handlePacketTransmissionNoReply(supv::TcBase& packet, + uint32_t timeoutExecutionReport = 60000); + int handleAckReception(supv::TcBase& tc, uint8_t serviceId, size_t packetLen); + int handleExeAckReception(supv::TcBase& tc, uint8_t serviceId, size_t packetLen); + + // ReturnValue_t sendCommand(ploc::SpTcBase& packet); /** * @brief Function which reads form the communication interface * @@ -278,7 +285,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, * @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 receive(uint8_t* data, size_t* readBytes, size_t requestBytes); ReturnValue_t handleAck(); ReturnValue_t handleExe(uint32_t timeout = 1000); /** @@ -293,7 +300,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, */ 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(); @@ -315,6 +322,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, ReturnValue_t handleRemainingExeReport(ploc::SpTmReader& reader); void resetSpParams(); + void pushIpcData(const uint8_t* data, size_t len); /** * @brief Device specific initialization, using the cookie. diff --git a/mission/devices/devicedefinitions/SpBase.h b/mission/devices/devicedefinitions/SpBase.h index f34e921a..22c138b5 100644 --- a/mission/devices/devicedefinitions/SpBase.h +++ b/mission/devices/devicedefinitions/SpBase.h @@ -50,6 +50,8 @@ class SpTcBase { uint16_t getApid() const { return spParams.creator.getApid(); } + uint16_t getSeqCount() const { return spParams.creator.getSequenceCount(); } + ReturnValue_t checkPayloadLen() { if (ccsds::HEADER_LEN + spParams.fullPayloadLen > spParams.maxSize) { return SerializeIF::BUFFER_TOO_SHORT; From 1d6258d2234b39a53ec890d5bcfd4755d5ce6883 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 16:56:42 +0100 Subject: [PATCH 041/176] start fixing dev handler ack handling --- .../PlocSupervisorDefinitions.h | 123 ++++++++++-------- linux/devices/ploc/PlocSupervisorHandler.cpp | 38 +++--- linux/devices/ploc/PlocSupvUartMan.cpp | 42 +++--- linux/devices/ploc/PlocSupvUartMan.h | 11 -- 4 files changed, 104 insertions(+), 110 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 2b248404..dfc7acce 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -56,18 +56,19 @@ 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); +static constexpr ReturnValue_t INVALID_REPLY_LENGTH = MAKE_RETURN_CODE(0xAF); //! [EXPORT] : [COMMENT] Received action command has invalid length -static const ReturnValue_t INVALID_LENGTH = MAKE_RETURN_CODE(0xAF); +static const ReturnValue_t INVALID_LENGTH = MAKE_RETURN_CODE(0xB0); //! [EXPORT] : [COMMENT] Filename too long -static const ReturnValue_t FILENAME_TOO_LONG = MAKE_RETURN_CODE(0xB0); +static const ReturnValue_t FILENAME_TOO_LONG = MAKE_RETURN_CODE(0xB1); //! [EXPORT] : [COMMENT] Received update status report with invalid packet length field -static const ReturnValue_t UPDATE_STATUS_REPORT_INVALID_LENGTH = MAKE_RETURN_CODE(0xB1); +static const ReturnValue_t UPDATE_STATUS_REPORT_INVALID_LENGTH = MAKE_RETURN_CODE(0xB2); //! [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); +static const ReturnValue_t UPDATE_CRC_FAILURE = MAKE_RETURN_CODE(0xB3); //! [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); +static const ReturnValue_t SUPV_HELPER_EXECUTING = MAKE_RETURN_CODE(0xB4); static constexpr ReturnValue_t BUF_TOO_SMALL = MAKE_RETURN_CODE(0xC0); static constexpr ReturnValue_t NO_REPLY_TIMEOUT = MAKE_RETURN_CODE(0xC1); @@ -470,6 +471,12 @@ class TmBase : public ploc::SpTmReader { uint8_t getServiceId() const { return getPacketData()[TIMESTAMP_LEN]; } 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; @@ -1110,7 +1117,8 @@ class VerificationReport { if (readerBase.getApid() != Apid::TMTC_MAN) { return result::INVALID_APID; } - if (readerBase.getBufSize() < MIN_PAYLOAD_LEN + 8) { + 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; @@ -1507,6 +1515,59 @@ class ExecutionReport : public VerificationReport { }; }; +class UpdateStatusReport { + public: + UpdateStatusReport(TmBase& tmReader) : tmReader(tmReader) {} + + ReturnValue_t parse() { + if (not tmReader.crcIsOk()) { + return result::CRC_FAILURE; + } + if (tmReader.getApid() != 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 = PAYLOAD_LEN; + if (remLen < PAYLOAD_LEN) { + return result::INVALID_REPLY_LENGTH; + } + 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; +}; + /** * @brief This dataset stores the boot status report of the supervisor. */ @@ -1661,56 +1722,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 result::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 result::UPDATE_STATUS_REPORT_INVALID_LENGTH; - } - return returnvalue::OK; - } -}; - /** * @brief This dataset stores the ADC report. */ diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index f0e56347..3e31437b 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -60,11 +60,6 @@ ReturnValue_t PlocSupervisorHandler::initialize() { 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) { @@ -928,25 +923,22 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) { using namespace supv; ReturnValue_t result = returnvalue::OK; + tmReader.setData(data, SIZE_ACK_REPORT); + if(tmReader.checkCrc() != returnvalue::OK) { + 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, result::CRC_FAILURE); + disableAllReplies(); + return returnvalue::OK; + } + AcknowledgmentReport ack(tmReader); + result = ack.parse(); + if (result != returnvalue::OK) { + return result; + } // TODO: Fix - - // AcknowledgmentReport ack(data, SIZE_ACK_REPORT); - // result = ack.checkSize(); - // if (result != returnvalue::OK) { - // return result; - // } - // - // result = ack.checkCrc(); - // if (result != returnvalue::OK) { - // 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); - // disableAllReplies(); - // return returnvalue::OK; - // } - // // result = ack.checkApid(); // // switch (result) { diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index ef571c11..622acc89 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -159,17 +159,6 @@ bool PlocSupvHelper::handleUartReception() { return false; } -// ReturnValue_t PlocSupvHelper::setComIF(UartComIF* 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; @@ -432,8 +421,7 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { update.bytesWritten); return result; } - // TODO: Fix - // result = handlePacketTransmission(packet); + result = encodeAndSendPacket(packet.getFullPacket(), packet.getFullPacketLen()); if (result != returnvalue::OK) { triggerEvent(WRITE_MEMORY_FAILED, buildProgParams1(progPercent, update.sequenceCount), update.bytesWritten); @@ -728,12 +716,7 @@ ReturnValue_t PlocSupvHelper::calcImageCrc() { ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { ReturnValue_t result = returnvalue::OK; - // TODO: Fix 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) { @@ -766,8 +749,7 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { } else if (retval == -1) { return returnvalue::FAILED; } - } else if (not checkReplyReceived) { - // if (serviceId == ) + } else if (checkReplyReceived) { retval = handleExeAckReception(packet, serviceId, packetLen); if (retval == 1) { break; @@ -775,6 +757,26 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { return returnvalue::FAILED; } } + } else if (tmReader.getApid() == Apid::MEM_MAN) { + if (ackReceived) { + supv::UpdateStatusReport report(tmReader); + result = report.parse(); + if (result != returnvalue::OK) { + return result; + } + if (update.crcShouldBeChecked) { + result = report.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) + << report.getCrc() << std::dec << std::endl; + return result; + } + } + checkReplyReceived = true; + } } else { pushIpcData(decodedBuf.data(), packetLen); decodedRingBuf.deleteData(packetLen); diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index 34d8bd2e..f8f175d5 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -277,17 +277,6 @@ class PlocSupvHelper : public DeviceCommunicationIF, int handleAckReception(supv::TcBase& tc, uint8_t serviceId, size_t packetLen); int handleExeAckReception(supv::TcBase& tc, uint8_t serviceId, size_t packetLen); - // 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); /** * @brief Handles reading of TM packets from the communication interface * From 54523b25d1cf3e6031e119337d49a6b5ac0c826d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 17:07:12 +0100 Subject: [PATCH 042/176] fixed ack reply handling --- .../PlocSupervisorDefinitions.h | 45 ++++++------ linux/devices/ploc/PlocSupervisorHandler.cpp | 70 +++++++------------ 2 files changed, 49 insertions(+), 66 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index dfc7acce..08146e5e 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -21,54 +21,55 @@ 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(0xA1); +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(0xA2); +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(0xA3); +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(0xA4); +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(0xA5); +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(0xA6); +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(0xA7); +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(0xA8); +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(0xA9); +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(0xAA); +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(0xAB); +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(0xAC); +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(0xAD); +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(0xAE); -static constexpr ReturnValue_t INVALID_REPLY_LENGTH = MAKE_RETURN_CODE(0xAF); +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(0xB0); +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(0xB1); +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(0xB2); +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(0xB3); +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(0xB4); +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); @@ -1165,8 +1166,6 @@ class VerificationReport { uint32_t getStatusCode() const { return statusCode; } - virtual ReturnValue_t checkApid() { return returnvalue::FAILED; } - protected: TmBase& readerBase; uint8_t refApid = 0; @@ -1183,7 +1182,7 @@ class AcknowledgmentReport : public VerificationReport { virtual ReturnValue_t parse() override { if (readerBase.getServiceId() != static_cast(tm::TmtcId::ACK) and readerBase.getServiceId() != static_cast(tm::TmtcId::NAK)) { - return returnvalue::FAILED; + return result::INVALID_SERVICE_ID; } return VerificationReport::parse(); } diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 3e31437b..d77ffb1c 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -924,54 +924,38 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) { ReturnValue_t result = returnvalue::OK; tmReader.setData(data, SIZE_ACK_REPORT); - if(tmReader.checkCrc() != returnvalue::OK) { - 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, result::CRC_FAILURE); - disableAllReplies(); - return returnvalue::OK; + if (tmReader.checkCrc() != returnvalue::OK) { + 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, result::CRC_FAILURE); + disableAllReplies(); + return returnvalue::OK; } AcknowledgmentReport ack(tmReader); result = ack.parse(); if (result != returnvalue::OK) { - return result; + 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())); + } + 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(); } - // TODO: Fix - // 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; - // } - // } return result; } From 27e46615b6ab94e629d4742e9f3000186d45c46b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 19:53:26 +0100 Subject: [PATCH 043/176] repaire exe handling --- .../PlocSupervisorDefinitions.h | 21 +++---- linux/devices/ploc/PlocSupervisorHandler.cpp | 59 +++++++++++-------- linux/devices/ploc/PlocSupervisorHandler.h | 6 +- 3 files changed, 51 insertions(+), 35 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 08146e5e..4b482a2b 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -12,8 +12,6 @@ #include "mission/devices/devicedefinitions/SpBase.h" -using namespace returnvalue; - namespace supv { namespace result { @@ -126,13 +124,16 @@ static const DeviceCommandId_t CONTINUE_UPDATE = 60; static const DeviceCommandId_t MEMORY_CHECK_WITH_FILE = 61; /** 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; @@ -493,7 +494,7 @@ class NoPayloadPacket : public TcBase { ReturnValue_t buildPacket() { ReturnValue_t result = checkSizeAndSerializeHeader(); - if (result != OK) { + if (result != returnvalue::OK) { return result; } return calcAndSetCrc(); diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index d77ffb1c..5374bc84 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -15,6 +15,7 @@ #include "fsfw/timemanager/Clock.h" using namespace supv; +using namespace returnvalue; PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie, Gpio uartIsolatorSwitch, @@ -29,7 +30,7 @@ PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t u adcReport(this), powerSwitch(powerSwitch), supvHelper(supvHelper) { - if (comCookie == NULL) { + if (comCookie == nullptr) { sif::error << "PlocSupervisorHandler: Invalid com cookie" << std::endl; } if (supvHelper == nullptr) { @@ -48,11 +49,6 @@ 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 sdcMan = SdCardManager::instance(); #endif /* TE0720_1CFA */ @@ -447,10 +443,9 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d } void PlocSupervisorHandler::fillCommandAndReplyMap() { - using namespace supv; - this->insertInCommandMap(GET_HK_REPORT); - this->insertInCommandMap(START_MPSOC); - this->insertInCommandMap(SHUTDOWN_MPSOC); + insertInCommandMap(GET_HK_REPORT); + insertInCommandMap(START_MPSOC); + insertInCommandMap(SHUTDOWN_MPSOC); this->insertInCommandMap(SEL_MPSOC_BOOT_IMAGE); this->insertInCommandMap(SET_BOOT_TIMEOUT); this->insertInCommandMap(SET_MAX_RESTART_TRIES); @@ -503,8 +498,7 @@ ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::ite uint8_t expectedReplies, bool useAlternateId, DeviceCommandId_t alternateReplyID) { - using namespace supv; - ReturnValue_t result = returnvalue::OK; + ReturnValue_t result = OK; uint8_t enabledReplies = 0; @@ -657,13 +651,13 @@ ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t r switch (tmReader.getServiceId()) { case (static_cast(supv::tm::TmtcId::ACK)): case (static_cast(supv::tm::TmtcId::NAK)): { - *foundLen = SIZE_ACK_REPORT; - *foundId = ACK_REPORT; + *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 = SIZE_EXE_REPORT; + *foundLen = tmReader.getFullPacketLen(); *foundId = EXE_REPORT; return OK; } @@ -672,8 +666,8 @@ ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t r } case (Apid::HK): { if (tmReader.getServiceId() == static_cast(supv::tm::HkId::REPORT)) { - *foundLen = SIZE_HK_REPORT; - *foundId = HK_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()); @@ -684,8 +678,8 @@ ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t r case (Apid::BOOT_MAN): { if (tmReader.getServiceId() == static_cast(supv::tm::BootManId::BOOT_STATUS_REPORT)) { - *foundLen = SIZE_BOOT_STATUS_REPORT; - *foundId = BOOT_STATUS_REPORT; + *foundLen = tmReader.getFullPacketLen(); + *foundId = ReplyId::BOOT_STATUS_REPORT; return OK; } break; @@ -693,6 +687,8 @@ ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t r case (Apid::MEM_MAN): { if (tmReader.getServiceId() == static_cast(supv::tm::MemManId::UPDATE_STATUS_REPORT)) { + *foundLen = tmReader.getFullPacketLen(); + *foundId = ReplyId::UPDATE_STATUS_REPORT; // TODO: I think this will be handled by the uart manager? // Actually, this is a bit tricky. Maybe the lower level will have two separate ring // buffers, one for internally handled packets and one for packets which are handled @@ -923,7 +919,6 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) { using namespace supv; ReturnValue_t result = returnvalue::OK; - tmReader.setData(data, SIZE_ACK_REPORT); if (tmReader.checkCrc() != returnvalue::OK) { sif::error << "PlocSupervisorHandler::handleAckReport: CRC failure" << std::endl; nextReplyId = supv::NONE; @@ -963,6 +958,23 @@ ReturnValue_t PlocSupervisorHandler::handleExecutionReport(const uint8_t* data) using namespace supv; ReturnValue_t result = returnvalue::OK; + if (tmReader.checkCrc() != OK) { + nextReplyId = supv::NONE; + return result::CRC_FAILURE; + } + ExecutionReport report(tmReader); + result = report.parse(); + if (result != OK) { + nextReplyId = supv::NONE; + return result; + } + 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; // TODO: Fix // ExecutionReport exe(data, SIZE_EXE_REPORT); // result = exe.checkSize(); @@ -2082,7 +2094,7 @@ ReturnValue_t PlocSupervisorHandler::eventSubscription() { return result; } -ReturnValue_t PlocSupervisorHandler::handleExecutionSuccessReport(const uint8_t* data) { +ReturnValue_t PlocSupervisorHandler::handleExecutionSuccessReport(ExecutionReport& report) { DeviceCommandId_t commandId = getPendingCommand(); switch (commandId) { case supv::READ_GPIO: { @@ -2130,11 +2142,12 @@ 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, result::RECEIVED_EXE_FAILURE); disableExeReportReply(); diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 4221bf4d..898ef13c 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -13,6 +13,8 @@ #include "fsfw_hal/linux/uart/UartComIF.h" #include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" +using supv::ExecutionReport; + /** * @brief This is the device handler for the supervisor of the PLOC which is programmed by * Thales. @@ -378,8 +380,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); }; From fd5cc19231c8e02ff025d6f79110330fbd46afbe Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 20:04:57 +0100 Subject: [PATCH 044/176] remove non-working commands --- .../PlocSupervisorDefinitions.h | 2 + linux/devices/ploc/PlocSupervisorHandler.cpp | 195 ++++++------------ linux/devices/ploc/PlocSupervisorHandler.h | 1 - 3 files changed, 65 insertions(+), 133 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 4b482a2b..7facd798 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -1248,6 +1248,8 @@ class ExecutionReport : public VerificationReport { public: ExecutionReport(TmBase& readerBase) : VerificationReport(readerBase) {} + 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)) { diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 5374bc84..3fed970e 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -443,55 +443,39 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d } void PlocSupervisorHandler::fillCommandAndReplyMap() { + // Command only insertInCommandMap(GET_HK_REPORT); insertInCommandMap(START_MPSOC); 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, + insertInCommandMap(SEL_MPSOC_BOOT_IMAGE); + insertInCommandMap(SET_BOOT_TIMEOUT); + insertInCommandMap(SET_MAX_RESTART_TRIES); + insertInCommandMap(RESET_MPSOC); + 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(SET_SHUTDOWN_TIMEOUT); + insertInCommandMap(FACTORY_FLASH); + insertInCommandMap(RESET_PL); + + // ACK replies, use countdown for them + insertInReplyMap(ACK_REPORT, 0, 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); + insertInReplyMap(EXE_REPORT, 0, nullptr, SIZE_EXE_REPORT, false, &executionReportTimeout); + + // 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, @@ -723,18 +707,10 @@ 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; @@ -749,22 +725,6 @@ ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id, 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; -} - -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})); @@ -975,40 +935,6 @@ ReturnValue_t PlocSupervisorHandler::handleExecutionReport(const uint8_t* data) } nextReplyId = supv::NONE; return result; - // TODO: Fix - // ExecutionReport exe(data, SIZE_EXE_REPORT); - // result = exe.checkSize(); - // if (result != returnvalue::OK) { - // return result; - // } - // - // result = exe.checkCrc(); - // if (result != returnvalue::OK) { - // sif::error << "PlocSupervisorHandler::handleExecutionReport: CRC failure" << std::endl; - // 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; - // } - // } - // nextReplyId = supv::NONE; - return result; } ReturnValue_t PlocSupervisorHandler::handleHkReport(const uint8_t* data) { @@ -2096,38 +2022,29 @@ ReturnValue_t PlocSupervisorHandler::eventSubscription() { ReturnValue_t PlocSupervisorHandler::handleExecutionSuccessReport(ExecutionReport& report) { DeviceCommandId_t commandId = getPendingCommand(); + ReturnValue_t result = OK; switch (commandId) { case supv::READ_GPIO: { // TODO: Fix - // 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(); - //#if OBSW_DEBUG_PLOC_SUPERVISOR == 1 - // sif::info << "PlocSupervisorHandler: Read GPIO TM, State: " << gpioState << std::endl; - //#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ - // DeviceCommandMap::iterator iter = deviceCommandMap.find(commandId); - // if (iter->second.sendReplyTo == NO_COMMAND_ID) { - // return returnvalue::OK; - // } - // uint8_t data[sizeof(gpioState)]; - // size_t size = 0; - // result = SerializeAdapter::serialize(&gpioState, data, &size, sizeof(gpioState), - // SerializeIF::Endianness::BIG); - // if (result != returnvalue::OK) { - // sif::debug << "PlocSupervisorHandler: Failed to deserialize GPIO state" << - // std::endl; - // } - // result = actionHelper.reportData(iter->second.sendReplyTo, commandId, data, - // sizeof(data)); if (result != returnvalue::OK) { - // sif::warning << "PlocSupervisorHandler: Read GPIO, failed to report data" << - // std::endl; - // } + 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 */ + DeviceCommandMap::iterator iter = deviceCommandMap.find(commandId); + if (iter->second.sendReplyTo == NO_COMMAND_ID) { + return returnvalue::OK; + } + uint8_t data[sizeof(gpioState)]; + size_t size = 0; + result = SerializeAdapter::serialize(&gpioState, data, &size, sizeof(gpioState), + SerializeIF::Endianness::BIG); + if (result != returnvalue::OK) { + sif::debug << "PlocSupervisorHandler: Failed to deserialize GPIO state" << std::endl; + } + result = actionHelper.reportData(iter->second.sendReplyTo, commandId, data, sizeof(data)); + if (result != returnvalue::OK) { + sif::warning << "PlocSupervisorHandler: Read GPIO, failed to report data" << std::endl; + } break; } case supv::SET_TIME_REF: { @@ -2179,3 +2096,17 @@ void PlocSupervisorHandler::printAckFailureInfo(uint16_t statusCode, DeviceComma 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; +} diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 898ef13c..178875d6 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -50,7 +50,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; From 52f15906d8f607e5cf1d1f269425d0c67026d635 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 20:14:42 +0100 Subject: [PATCH 045/176] kick out more commands --- linux/devices/ploc/PlocSupervisorHandler.cpp | 32 ++++++-------------- 1 file changed, 10 insertions(+), 22 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 3fed970e..24d3f198 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -139,18 +139,6 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, plocSupvHelperExecuting = true; return EXECUTION_FINISHED; } - // case LOGGING_REQUEST_EVENT_BUFFERS: { - // if (size > config::MAX_PATH_SIZE) { - // return result::FILENAME_TOO_LONG; - // } - // result = supvHelper->startEventBufferRequest( - // std::string(reinterpret_cast(data), size)); - // if (result != returnvalue::OK) { - // return result; - // } - // plocSupvHelperExecuting = true; - // return EXECUTION_FINISHED; - // } default: break; } @@ -568,25 +556,25 @@ 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 WIPE_MRAM: case SET_GPIO: 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 FACTORY_RESET_CLEAR_ALL: + //case FACTORY_RESET_CLEAR_MIRROR: + //case FACTORY_RESET_CLEAR_CIRCULAR: 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: From d3da5bd2d86ac3a648b0ef553d42a5d0de502c3b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 20:37:57 +0100 Subject: [PATCH 046/176] add factory reset cmd --- .../PlocSupervisorDefinitions.h | 63 ++++++++++++------- linux/devices/ploc/PlocSupervisorHandler.cpp | 44 +++++++++---- linux/devices/ploc/PlocSupervisorHandler.h | 2 + 3 files changed, 73 insertions(+), 36 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 7facd798..fa4c728b 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -102,10 +102,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; @@ -144,27 +142,6 @@ 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; @@ -292,6 +269,21 @@ 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; uint8_t memId; @@ -646,6 +638,29 @@ class SetBootTimeout : public TcBase { } }; +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. */ diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 24d3f198..8a3613ad 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -310,6 +310,10 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d result = returnvalue::OK; break; } + case FACTORY_RESET: { + result = prepareFactoryResetCmd(commandData, commandDataLen); + break; + } case READ_GPIO: { prepareReadGpioCmd(commandData); result = returnvalue::OK; @@ -449,13 +453,13 @@ void PlocSupervisorHandler::fillCommandAndReplyMap() { insertInCommandMap(RUN_AUTO_EM_TESTS); insertInCommandMap(SET_GPIO); insertInCommandMap(READ_GPIO); + insertInCommandMap(FACTORY_RESET); insertInCommandMap(SET_SHUTDOWN_TIMEOUT); insertInCommandMap(FACTORY_FLASH); insertInCommandMap(RESET_PL); // ACK replies, use countdown for them - insertInReplyMap(ACK_REPORT, 0, nullptr, SIZE_ACK_REPORT, false, - &acknowledgementReportTimeout); + insertInReplyMap(ACK_REPORT, 0, nullptr, SIZE_ACK_REPORT, false, &acknowledgementReportTimeout); insertInReplyMap(EXE_REPORT, 0, nullptr, SIZE_EXE_REPORT, false, &executionReportTimeout); // TM replies @@ -556,25 +560,26 @@ 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 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 FACTORY_RESET_CLEAR_ALL: + // case FACTORY_RESET_CLEAR_MIRROR: + // case FACTORY_RESET_CLEAR_CIRCULAR: 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: @@ -1565,6 +1570,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; diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 178875d6..99b222c6 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -264,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. From e2a0db8fcc15380a145e779fb1dbf7918990be11 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 8 Nov 2022 20:41:20 +0100 Subject: [PATCH 047/176] command and function graveyard --- linux/devices/ploc/PlocSupervisorHandler.cpp | 329 ++++++++++--------- 1 file changed, 165 insertions(+), 164 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 8a3613ad..5ea9d539 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -262,49 +262,15 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d result = prepareSetAlertLimitCmd(commandData); break; } - // case SET_ADC_ENABLED_CHANNELS: { - // prepareSetAdcEnabledChannelsCmd(commandData); - // result = returnvalue::OK; - // break; - // } - // case SET_ADC_WINDOW_AND_STRIDE: { - // prepareSetAdcWindowAndStrideCmd(commandData); - // result = returnvalue::OK; - // break; - // } - // case SET_ADC_THRESHOLD: { - // prepareSetAdcThresholdCmd(commandData); - // result = returnvalue::OK; - // break; - // } case GET_LATCHUP_STATUS_REPORT: { prepareEmptyCmd(Apid::LATCHUP_MON, static_cast(tc::LatchupMonId::GET_STATUS_REPORT)); result = returnvalue::OK; 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 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; @@ -319,6 +285,25 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d 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 ENABLE_NVMS: { + // result = prepareEnableNvmsCommand(commandData); + // break; + // } // case RESTART_SUPERVISOR: { // prepareEmptyCmd(APID_RESTART_SUPERVISOR); // result = returnvalue::OK; @@ -357,16 +342,22 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d // 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 SET_ADC_ENABLED_CHANNELS: { + + // prepareSetAdcEnabledChannelsCmd(commandData); + // result = returnvalue::OK; + // break; + // } + // case SET_ADC_WINDOW_AND_STRIDE: { + // prepareSetAdcWindowAndStrideCmd(commandData); + // result = returnvalue::OK; + // break; + // } + // case SET_ADC_THRESHOLD: { + // prepareSetAdcThresholdCmd(commandData); + // result = returnvalue::OK; + // break; + // } // case ENABLE_AUTO_TM: { // EnableAutoTm packet(spParams); // result = packet.buildPacket(); @@ -416,15 +407,25 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d // finishTcPrep(packet.getFullPacketLen()); // break; // } - case RESET_PL: { - prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::RESET_PL)); - result = returnvalue::OK; - break; - } - // case ENABLE_NVMS: { - // result = prepareEnableNvmsCommand(commandData); + // 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 WIPE_MRAM: { + // result = prepareWipeMramCmd(commandData); + // break; + // } + // case FIRST_MRAM_DUMP: + // case CONSECUTIVE_MRAM_DUMP: + // result = prepareDumpMramCmd(commandData); + // break; default: sif::debug << "PlocSupervisorHandler::buildCommandFromCommand: Command not implemented" << std::endl; @@ -1503,48 +1504,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); @@ -1611,33 +1570,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; @@ -1726,41 +1658,6 @@ 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 >= 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::handleMramDumpPacket(DeviceCommandId_t id) { ReturnValue_t result = returnvalue::FAILED; @@ -1837,15 +1734,6 @@ void PlocSupervisorHandler::increaseExpectedMramReplies(DeviceCommandId_t id) { return; } -// 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::handleMramDumpFile(DeviceCommandId_t id) { #ifdef XIPHOS_Q7S if (not sdcMan->getActiveSdCard()) { @@ -2118,3 +2006,116 @@ ReturnValue_t PlocSupervisorHandler::getSwitches(const uint8_t** switches, 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::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::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; +// } From ea6fd8c952efe9f24ce2f700d6ba80e6e99f2b82 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 9 Nov 2022 13:07:20 +0100 Subject: [PATCH 048/176] smaller fixes and improvements --- bsp_q7s/core/CoreController.cpp | 22 ++++++++++------------ bsp_q7s/core/CoreController.h | 6 +++++- fsfw | 2 +- linux/devices/ScexUartReader.cpp | 6 +++++- mission/devices/ScexDeviceHandler.cpp | 13 ++++++++++--- mission/devices/ScexDeviceHandler.h | 1 + tmtc | 2 +- 7 files changed, 33 insertions(+), 19 deletions(-) diff --git a/bsp_q7s/core/CoreController.cpp b/bsp_q7s/core/CoreController.cpp index 5a807b64..05660705 100644 --- a/bsp_q7s/core/CoreController.cpp +++ b/bsp_q7s/core/CoreController.cpp @@ -47,10 +47,7 @@ CoreController::CoreController(object_id_t objectId) sdcMan->setBlocking(false); } - result = initBootCopy(); - if (result != returnvalue::OK) { - sif::warning << "CoreController::CoreController: Boot copy init" << std::endl; - } + getCurrentBootCopy(CURRENT_CHIP, CURRENT_COPY); } catch (const std::filesystem::filesystem_error &e) { sif::error << "CoreController::CoreController: Failed with exception " << e.what() << std::endl; } @@ -95,9 +92,9 @@ void CoreController::performControlOperation() { ReturnValue_t CoreController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { - localDataPoolMap.emplace(core::TEMPERATURE, new PoolEntry({0})); - localDataPoolMap.emplace(core::PS_VOLTAGE, new PoolEntry({0})); - localDataPoolMap.emplace(core::PL_VOLTAGE, new PoolEntry({0})); + localDataPoolMap.emplace(core::TEMPERATURE, &tempPoolEntry); + localDataPoolMap.emplace(core::PS_VOLTAGE, &psVoltageEntry); + localDataPoolMap.emplace(core::PL_VOLTAGE, &plVoltageEntry); poolManager.subscribeForRegularPeriodicPacket({hkSet.getSid(), false, 10.0}); return returnvalue::OK; } @@ -175,8 +172,7 @@ ReturnValue_t CoreController::initializeAfterTaskCreation() { setenv("PATH", updatedEnvPath.c_str(), true); updateProtInfo(); initPrint(); - ExtendedControllerBase::initializeAfterTaskCreation(); - return result; + return ExtendedControllerBase::initializeAfterTaskCreation(); } ReturnValue_t CoreController::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy, @@ -797,7 +793,7 @@ ReturnValue_t CoreController::actionListDirectoryIntoFile(ActionId_t actionId, return returnvalue::OK; } -ReturnValue_t CoreController::initBootCopy() { +ReturnValue_t CoreController::initBootCopyFile() { if (not std::filesystem::exists(CURR_COPY_FILE)) { // This file is created by the systemd service eive-early-config so this should // not happen normally @@ -807,8 +803,6 @@ ReturnValue_t CoreController::initBootCopy() { utility::handleSystemError(result, "CoreController::initBootCopy"); } } - - getCurrentBootCopy(CURRENT_CHIP, CURRENT_COPY); return returnvalue::OK; } @@ -1244,6 +1238,10 @@ void CoreController::performMountedSdCardOperations() { std::filesystem::create_directory(path.str()); } initVersionFile(); + ReturnValue_t result = initBootCopyFile(); + if (result != returnvalue::OK) { + sif::warning << "CoreController::CoreController: Boot copy init" << std::endl; + } initClockFromTimeFile(); performRebootFileHandling(false); } diff --git a/bsp_q7s/core/CoreController.h b/bsp_q7s/core/CoreController.h index c3c830cc..4d9d5ee8 100644 --- a/bsp_q7s/core/CoreController.h +++ b/bsp_q7s/core/CoreController.h @@ -226,6 +226,10 @@ class CoreController : public ExtendedControllerBase { PeriodicOperationDivider opDivider5; PeriodicOperationDivider opDivider10; + PoolEntry tempPoolEntry = PoolEntry(0.0); + PoolEntry psVoltageEntry = PoolEntry(0.0); + PoolEntry plVoltageEntry = PoolEntry(0.0); + core::HkSet hkSet; #if OBSW_SD_CARD_MUST_BE_ON == 1 @@ -243,7 +247,7 @@ class CoreController : public ExtendedControllerBase { ReturnValue_t initClockFromTimeFile(); ReturnValue_t performSdCardCheck(); ReturnValue_t timeFileHandler(); - ReturnValue_t initBootCopy(); + ReturnValue_t initBootCopyFile(); ReturnValue_t initWatchdogFifo(); ReturnValue_t initSdCardBlocking(); bool startSdStateMachine(sd::SdCard targetActiveSd, SdCfgMode mode, MessageQueueId_t commander, diff --git a/fsfw b/fsfw index 84b9d1ce..0e8f5ddd 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 84b9d1ce216c076bdfeeaf1663aa873c7f1c9cff +Subproject commit 0e8f5ddd26d586dd40e69f52aef1a63c0d5a9da6 diff --git a/linux/devices/ScexUartReader.cpp b/linux/devices/ScexUartReader.cpp index d128fa63..38a4025f 100644 --- a/linux/devices/ScexUartReader.cpp +++ b/linux/devices/ScexUartReader.cpp @@ -58,7 +58,7 @@ ReturnValue_t ScexUartReader::performOperation(uint8_t operationCode) { result = tryDleParsing(); } - TaskFactory::delayTask(400); + TaskFactory::delayTask(150); } else if (bytesRead < 0) { sif::warning << "ScexUartReader::performOperation: read call failed with error [" << errno << ", " << strerror(errno) << "]" << std::endl; @@ -213,6 +213,10 @@ ReturnValue_t ScexUartReader::tryDleParsing() { void ScexUartReader::reset() { lock->lockMutex(); state = States::FINISH; + ipcRingBuf.clear(); + while (not ipcQueue.empty()) { + ipcQueue.pop(); + } lock->unlockMutex(); } diff --git a/mission/devices/ScexDeviceHandler.cpp b/mission/devices/ScexDeviceHandler.cpp index 8819cd95..8da6d229 100644 --- a/mission/devices/ScexDeviceHandler.cpp +++ b/mission/devices/ScexDeviceHandler.cpp @@ -28,6 +28,7 @@ void ScexDeviceHandler::doStartUp() { setMode(MODE_ON); } void ScexDeviceHandler::doShutDown() { reader.reset(); commandActive = false; + multiFileFinishOutstanding = false; setMode(_MODE_POWER_DOWN); } @@ -96,6 +97,7 @@ ReturnValue_t ScexDeviceHandler::buildCommandFromCommand(DeviceCommandId_t devic << remainingMillis << std::endl; } + multiFileFinishOutstanding = true; prepareScexCmd(cmdTyped, {cmdBuf.data(), cmdBuf.size()}, rawPacketLen, {commandData + 1, commandDataLen - 1}, tempCheck); updatePeriodicReply(true, deviceCommand); @@ -105,6 +107,7 @@ ReturnValue_t ScexDeviceHandler::buildCommandFromCommand(DeviceCommandId_t devic finishCountdown.setTimeout(LONG_CD); // countdown starts finishCountdown.resetTimer(); + multiFileFinishOutstanding = true; prepareScexCmd(cmdTyped, {cmdBuf.data(), cmdBuf.size()}, rawPacketLen, {commandData + 1, commandDataLen - 1}, tempCheck); updatePeriodicReply(true, deviceCommand); @@ -114,6 +117,7 @@ ReturnValue_t ScexDeviceHandler::buildCommandFromCommand(DeviceCommandId_t devic finishCountdown.setTimeout(LONG_CD); // countdown starts finishCountdown.resetTimer(); + multiFileFinishOutstanding = true; prepareScexCmd(cmdTyped, {cmdBuf.data(), cmdBuf.size()}, rawPacketLen, {commandData + 1, commandDataLen - 1}, tempCheck); updatePeriodicReply(true, deviceCommand); @@ -173,17 +177,14 @@ ReturnValue_t ScexDeviceHandler::handleValidReply(size_t remSize, DeviceCommandI sif::info << "ScexDeviceHandler::handleValidReply: RemMillis: " << remainingMillis << std::endl; } - finishAction(true, helper.getCmd(), OK); result = APERIODIC_REPLY; break; } case (ONE_CELL): { - finishAction(true, helper.getCmd(), OK); result = APERIODIC_REPLY; break; } case (ALL_CELLS_CMD): { - finishAction(true, helper.getCmd(), OK); result = APERIODIC_REPLY; break; } @@ -191,6 +192,11 @@ ReturnValue_t ScexDeviceHandler::handleValidReply(size_t remSize, DeviceCommandI break; } } + if (result == APERIODIC_REPLY and multiFileFinishOutstanding) { + finishAction(true, helper.getCmd(), OK); + multiFileFinishOutstanding = false; + } + *foundId = helper.getCmd(); *foundLen = remSize; return result; @@ -250,6 +256,7 @@ ReturnValue_t ScexDeviceHandler::interpretDeviceReply(DeviceCommandId_t id, cons } return OK; }; + id = helper.getCmd(); switch (id) { case (PING): { status = oneFileHandler("ping_"); diff --git a/mission/devices/ScexDeviceHandler.h b/mission/devices/ScexDeviceHandler.h index 1c96618e..a164c5e2 100644 --- a/mission/devices/ScexDeviceHandler.h +++ b/mission/devices/ScexDeviceHandler.h @@ -28,6 +28,7 @@ class ScexDeviceHandler : public DeviceHandlerBase { std::string fileName = ""; bool fileNameSet = false; bool commandActive = false; + bool multiFileFinishOutstanding = false; bool debugMode = false; scex::Cmds currCmd = scex::Cmds::PING; diff --git a/tmtc b/tmtc index f62c67a1..f6fab2d4 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit f62c67a11e54b99fdb60dab13e55456f16450951 +Subproject commit f6fab2d44aff98174835c8446fd69c1ff589521b From 4a070f2b7f1c79bfcf515249201e76259c0c52b5 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 9 Nov 2022 14:53:08 +0100 Subject: [PATCH 049/176] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index f6fab2d4..b6490a05 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit f6fab2d44aff98174835c8446fd69c1ff589521b +Subproject commit b6490a05ec3ed8fca30719bc657ed9e13d5a32ad From b6dc81da0e355436e7a8c599b015debd6348c269 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 9 Nov 2022 15:23:40 +0100 Subject: [PATCH 050/176] keep old baud for FM --- common/config/devConf.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/config/devConf.h b/common/config/devConf.h index e7f7de5f..88e78e1e 100644 --- a/common/config/devConf.h +++ b/common/config/devConf.h @@ -55,7 +55,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_115200; +static constexpr UartBaudRate SCEX_BAUD = UartBaudRate::RATE_38400; 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; From c42eae9c1735ba4fd73af0161ff43e6d973e8986 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 9 Nov 2022 19:24:48 +0100 Subject: [PATCH 051/176] re-enabled some commands --- .../PlocSupervisorDefinitions.h | 62 +++++++++---------- linux/devices/ploc/PlocSupervisorHandler.cpp | 52 ++++++++-------- linux/devices/ploc/PlocSupervisorHandler.h | 2 +- 3 files changed, 57 insertions(+), 59 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index fa4c728b..8a642647 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -882,6 +882,37 @@ class RunAutoEmTests : public TcBase { void initPacket(uint8_t test) { payloadStart[0] = test; } }; +/** + * @brief This class packages the space packet to enable or disable ADC channels. + */ +class SetAdcEnabledChannels : public TcBase { + public: + /** + * @brief Constructor + * + * @param ch Defines channels to be enabled or disabled. + */ + SetAdcEnabledChannels(TcParams params) + : TcBase(params, Apid::ADC_MON, static_cast(tc::AdcMonId::SET_ENABLED_CHANNELS), 2) { + } + + ReturnValue_t buildPacket(uint16_t ch) { + auto res = checkSizeAndSerializeHeader(); + if (res != returnvalue::OK) { + return res; + } + initPacket(ch); + return calcAndSetCrc(); + } + + private: + 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 change the state of a GPIO. This command is only * required for ground testing. @@ -2000,37 +2031,6 @@ class DisableAutoTm : public TcBase { static const uint8_t DISABLE = 0; }; -/** - * @brief This class packages the space packet to enable or disable ADC channels. - */ -class SetAdcEnabledChannels : public TcBase { - public: - /** - * @brief Constructor - * - * @param ch Defines channels to be enabled or disabled. - */ - SetAdcEnabledChannels(TcParams params) - : TcBase(params, Apid::ADC_MON, static_cast(tc::AdcMonId::SET_ENABLED_CHANNELS), 2) { - } - - ReturnValue_t buildPacket(uint16_t ch) { - auto res = checkSizeAndSerializeHeader(); - if (res != returnvalue::OK) { - return res; - } - initPacket(ch); - return calcAndSetCrc(); - } - - private: - void initPacket(uint16_t ch) { - size_t serializedSize = 0; - SerializeAdapter::serialize(&ch, &payloadStart, &serializedSize, sizeof(ch), - SerializeIF::Endianness::BIG); - } -}; - /** * @brief This class creates the space packet to request the logging data from the supervisor */ diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 5ea9d539..dbb86ac2 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -299,6 +299,21 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d prepareEmptyCmd(Apid::BOOT_MAN, static_cast(tc::BootManId::RESET_PL)); result = returnvalue::OK; break; + } + case SET_ADC_ENABLED_CHANNELS: { + prepareSetAdcEnabledChannelsCmd(commandData); + result = returnvalue::OK; + break; + } + case SET_ADC_WINDOW_AND_STRIDE: { + prepareSetAdcWindowAndStrideCmd(commandData); + result = returnvalue::OK; + break; + } + case SET_ADC_THRESHOLD: { + prepareSetAdcThresholdCmd(commandData); + result = returnvalue::OK; + break; } // case ENABLE_NVMS: { // result = prepareEnableNvmsCommand(commandData); @@ -342,22 +357,6 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d // result = returnvalue::OK; // break; // } - // case SET_ADC_ENABLED_CHANNELS: { - - // prepareSetAdcEnabledChannelsCmd(commandData); - // result = returnvalue::OK; - // break; - // } - // case SET_ADC_WINDOW_AND_STRIDE: { - // prepareSetAdcWindowAndStrideCmd(commandData); - // result = returnvalue::OK; - // break; - // } - // case SET_ADC_THRESHOLD: { - // prepareSetAdcThresholdCmd(commandData); - // result = returnvalue::OK; - // break; - // } // case ENABLE_AUTO_TM: { // EnableAutoTm packet(spParams); // result = packet.buildPacket(); @@ -1452,17 +1451,16 @@ ReturnValue_t PlocSupervisorHandler::prepareSetAlertLimitCmd(const uint8_t* comm return returnvalue::OK; } -// ReturnValue_t PlocSupervisorHandler::prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData) -// { -// uint16_t ch = *(commandData) << 8 | *(commandData + 1); -// supv::SetAdcEnabledChannels packet(spParams); -// ReturnValue_t result = packet.buildPacket(ch); -// if (result != returnvalue::OK) { -// return result; -// } -// finishTcPrep(packet.getFullPacketLen()); -// return returnvalue::OK; -// } +ReturnValue_t PlocSupervisorHandler::prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData) { + uint16_t ch = *(commandData) << 8 | *(commandData + 1); + supv::SetAdcEnabledChannels packet(spParams); + ReturnValue_t result = packet.buildPacket(ch); + if (result != returnvalue::OK) { + return result; + } + finishTcPrep(packet.getFullPacketLen()); + return returnvalue::OK; +} ReturnValue_t PlocSupervisorHandler::prepareSetAdcWindowAndStrideCmd(const uint8_t* commandData) { uint8_t offset = 0; diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 99b222c6..9480667c 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -281,7 +281,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t prepareLatchupConfigCmd(const uint8_t* commandData, DeviceCommandId_t deviceCommand); ReturnValue_t prepareSetAlertLimitCmd(const uint8_t* commandData); - // ReturnValue_t prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData); + ReturnValue_t prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData); ReturnValue_t prepareSetAdcWindowAndStrideCmd(const uint8_t* commandData); ReturnValue_t prepareSetAdcThresholdCmd(const uint8_t* commandData); ReturnValue_t prepareRunAutoEmTest(const uint8_t* commandData); From 9e006d93fe2e86961bbc744e1e1ae5850b546d5b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 9 Nov 2022 19:27:18 +0100 Subject: [PATCH 052/176] move other function to graveyard --- linux/devices/ploc/PlocSupervisorHandler.cpp | 72 ++++++++++---------- 1 file changed, 36 insertions(+), 36 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index dbb86ac2..86547b73 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -1156,42 +1156,6 @@ 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::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; -// } - ReturnValue_t PlocSupervisorHandler::handleAdcReport(const uint8_t* data) { ReturnValue_t result = returnvalue::OK; @@ -2117,3 +2081,39 @@ uint32_t PlocSupervisorHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t mod // 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; +// } From b88b4cc06d005fe52d8dfd12ab68acaaa14e29aa Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 9 Nov 2022 19:47:42 +0100 Subject: [PATCH 053/176] tweaks and fixes for UART man --- linux/devices/ploc/PlocSupvUartMan.cpp | 105 +++++++++---------------- 1 file changed, 35 insertions(+), 70 deletions(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 622acc89..9630d674 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -65,7 +65,7 @@ ReturnValue_t PlocSupvHelper::initializeInterface(CookieIF* cookie) { // Use non-canonical mode and clear echo flag tty.c_lflag &= ~(ICANON | ECHO); - // Non-blocking mode, 0.5 seconds timeout + // Blocking mode, 0.5 seconds timeout tty.c_cc[VTIME] = 5; tty.c_cc[VMIN] = 0; @@ -311,12 +311,7 @@ void PlocSupvHelper::executeFullCheckMemoryCommand() { 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); - } + handleCheckMemoryCommand(); } ReturnValue_t PlocSupvHelper::executeUpdate() { @@ -434,6 +429,7 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { #if OBSW_DEBUG_PLOC_SUPERVISOR == 1 progressPrinter.print(update.bytesWritten); #endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + TaskFactory::delayTask(1); } return result; } @@ -552,7 +548,11 @@ ReturnValue_t PlocSupvHelper::handlePacketTransmissionNoReply(supv::TcBase& pack } Countdown countdown(timeoutExecutionReport); bool ackReceived = false; + bool packetWasHandled = false; while (true) { + while (result != NO_PACKET_FOUND) { + result = tryHdlcParsing(); + } if (not decodedQueue.empty()) { size_t packetLen = 0; decodedQueue.retrieve(&packetLen); @@ -569,6 +569,7 @@ ReturnValue_t PlocSupvHelper::handlePacketTransmissionNoReply(supv::TcBase& pack retval = handleAckReception(packet, serviceId, packetLen); if (retval == 1) { ackReceived = true; + packetWasHandled = true; } else if (retval == -1) { return returnvalue::FAILED; } @@ -580,7 +581,8 @@ ReturnValue_t PlocSupvHelper::handlePacketTransmissionNoReply(supv::TcBase& pack return returnvalue::FAILED; } } - } else { + } + if (not packetWasHandled) { pushIpcData(decodedBuf.data(), packetLen); decodedRingBuf.deleteData(packetLen); } @@ -601,7 +603,7 @@ int PlocSupvHelper::handleAckReception(supv::TcBase& tc, uint8_t serviceId, size ReturnValue_t result = ackReport.parse(); if (result != returnvalue::OK) { triggerEvent(ACK_RECEPTION_FAILURE); - return returnvalue::FAILED; + return -1; } if (ackReport.getRefApid() == tc.getApid() and ackReport.getRefServiceId() == tc.getServiceId()) { @@ -631,7 +633,7 @@ int PlocSupvHelper::handleExeAckReception(supv::TcBase& tc, uint8_t serviceId, s ReturnValue_t result = exeReport.parse(); if (result != returnvalue::OK) { triggerEvent(EXE_RECEPTION_FAILURE); - return returnvalue::FAILED; + return -1; } if (exeReport.getRefApid() == tc.getApid() and exeReport.getRefServiceId() == tc.getServiceId()) { @@ -729,7 +731,12 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { Countdown countdown(timeout::CRC_EXECUTION_TIMEOUT); bool ackReceived = false; bool checkReplyReceived = false; + bool packetWasHandled = false; + bool exeReceived = false; while (true) { + while (result != NO_PACKET_FOUND) { + result = tryHdlcParsing(); + } if (not decodedQueue.empty()) { size_t packetLen = 0; decodedQueue.retrieve(&packetLen); @@ -739,19 +746,23 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { if (result != returnvalue::OK) { continue; } + packetWasHandled = false; if (tmReader.getApid() == Apid::TMTC_MAN) { uint8_t serviceId = tmReader.getServiceId(); int retval = 0; if (not ackReceived) { retval = handleAckReception(packet, serviceId, packetLen); if (retval == 1) { + packetWasHandled = true; ackReceived = true; } else if (retval == -1) { return returnvalue::FAILED; } - } else if (checkReplyReceived) { + } else { retval = handleExeAckReception(packet, serviceId, packetLen); if (retval == 1) { + packetWasHandled = true; + exeReceived = true; break; } else if (retval == -1) { return returnvalue::FAILED; @@ -764,86 +775,40 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { if (result != returnvalue::OK) { return result; } + packetWasHandled = true; + checkReplyReceived = true; if (update.crcShouldBeChecked) { result = report.verifyCrc(update.crc); - if (result != returnvalue::OK) { + if (result == returnvalue::OK) { + triggerEvent(SUPV_MEM_CHECK_OK, result); + return 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; - return result; + triggerEvent(SUPV_MEM_CHECK_FAIL, result); } } - checkReplyReceived = true; } - } else { + } + if (not packetWasHandled) { pushIpcData(decodedBuf.data(), packetLen); decodedRingBuf.deleteData(packetLen); } } else { TaskFactory::delayTask(50); } + if (ackReceived and exeReceived and checkReplyReceived) { + break; + } if (countdown.hasTimedOut()) { return result::NO_REPLY_TIMEOUT; } } return returnvalue::OK; - // result = handleAck(); - // if (result != returnvalue::OK) { - // return result; - // } - // - // bool exeAlreadyHandled = false; - // uint32_t timeout = std::max(CRC_EXECUTION_TIMEOUT, supv::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::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; } From 3be45b32ef166456b6d1c2c4073388a2198957c8 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 11:20:27 +0100 Subject: [PATCH 054/176] renaming --- linux/devices/ploc/PlocSupvUartMan.cpp | 12 ++++++------ linux/devices/ploc/PlocSupvUartMan.h | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 9630d674..a60618e1 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -109,7 +109,7 @@ ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { putTaskToSleep = true; break; } - case InternalState::LONGER_REQUEST: { + case InternalState::DEDICATED_REQUEST: { if (handleRunningLongerRequest() == REQUEST_DONE) { MutexGuard mg(lock); state = InternalState::DEFAULT; @@ -219,7 +219,7 @@ ReturnValue_t PlocSupvHelper::performUpdate(const supv::UpdateParams& params) { update.packetNum = 1; update.deleteMemory = params.deleteMemory; update.sequenceCount = params.seqCount; - state = InternalState::LONGER_REQUEST; + state = InternalState::DEDICATED_REQUEST; request = Request::UPDATE; } return result; @@ -243,7 +243,7 @@ ReturnValue_t PlocSupvHelper::performMemCheck(std::string file, uint8_t memoryId MutexGuard mg(lock); update.file = file; update.fullFileSize = getFileSize(file); - state = InternalState::LONGER_REQUEST; + state = InternalState::DEDICATED_REQUEST; request = Request::CHECK_MEMORY; update.memoryId = memoryId; update.startAddress = startAddress; @@ -261,7 +261,7 @@ ReturnValue_t PlocSupvHelper::initiateUpdateContinuation() { return HasActionsIF::IS_BUSY; } MutexGuard mg(lock); - state = InternalState::LONGER_REQUEST; + state = InternalState::DEDICATED_REQUEST; request = Request::CONTINUE_UPDATE; return returnvalue::OK; } @@ -884,7 +884,7 @@ ReturnValue_t PlocSupvHelper::sendMessage(CookieIF* cookie, const uint8_t* sendD return FAILED; } lock->lockMutex(); - if (state == InternalState::SLEEPING or state == InternalState::LONGER_REQUEST) { + if (state == InternalState::SLEEPING or state == InternalState::DEDICATED_REQUEST) { lock->unlockMutex(); return FAILED; } @@ -979,7 +979,7 @@ ReturnValue_t PlocSupvHelper::tryHdlcParsing() { ReturnValue_t result = parseRecRingBufForHdlc(bytesRead); if (result == returnvalue::OK) { // Packet found, advance read pointer. - if (state == InternalState::LONGER_REQUEST) { + if (state == InternalState::DEDICATED_REQUEST) { decodedRingBuf.writeData(decodedBuf.data(), bytesRead); decodedQueue.insert(bytesRead); } else { diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index f8f175d5..30d5fe1f 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -214,7 +214,7 @@ class PlocSupvHelper : public DeviceCommunicationIF, EventBufferRequest eventBufferReq; - enum class InternalState { SLEEPING, DEFAULT, LONGER_REQUEST, GO_TO_SLEEP }; + enum class InternalState { SLEEPING, DEFAULT, DEDICATED_REQUEST, GO_TO_SLEEP }; enum class Request { DEFAULT, From a2b0e53301967c4036fe5053b9848978197c7640 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 13:08:17 +0100 Subject: [PATCH 055/176] bugfix SW update --- linux/devices/ploc/PlocSupvUartMan.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index a60618e1..d0c96e93 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -416,12 +416,14 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { update.bytesWritten); return result; } - result = encodeAndSendPacket(packet.getFullPacket(), packet.getFullPacketLen()); + result = handlePacketTransmissionNoReply(packet); + //result = encodeAndSendPacket(packet.getFullPacket(), packet.getFullPacketLen()); if (result != returnvalue::OK) { triggerEvent(WRITE_MEMORY_FAILED, buildProgParams1(progPercent, update.sequenceCount), update.bytesWritten); return result; } + update.sequenceCount++; update.packetNum += 1; update.bytesWritten += dataLength; From 47b65a1fa3c8d1207860cd1381e8c7f379f0f9b6 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 13:09:31 +0100 Subject: [PATCH 056/176] create cam switcher, create new PL task --- bsp_q7s/core/InitMission.cpp | 7 +++++++ bsp_q7s/core/ObjectFactory.cpp | 5 ++++- bsp_q7s/core/ObjectFactory.h | 2 +- bsp_q7s/fmObjectFactory.cpp | 4 ++-- mission/system/objects/CamSwitcher.cpp | 4 ++-- mission/system/objects/CamSwitcher.h | 2 +- 6 files changed, 17 insertions(+), 7 deletions(-) diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index 4a0dbeff..9740912a 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -278,6 +278,13 @@ void initmission::initTasks() { } #endif /* OBSW_ADD_PLOC_SUPERVISOR */ + PeriodicTaskIF* plTask = factory->createPeriodicTask( + "PL_TASK", 25, 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); + } + #if OBSW_TEST_CCSDS_BRIDGE == 1 PeriodicTaskIF* ptmeTestTask = factory->createPeriodicTask( "PTME_TEST", 80, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc); diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index 3f6b2ac6..13998027 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -1,5 +1,7 @@ #include "ObjectFactory.h" +#include + #include "OBSWConfig.h" #include "bsp_q7s/boardtest/Q7STestTask.h" #include "bsp_q7s/callbacks/gnssCallback.h" @@ -583,9 +585,10 @@ void ObjectFactory::createSyrlinksComponents(PowerSwitchIF* pwrSwitcher) { #endif } -void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF) { +void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF& pwrSwitch) { using namespace gpio; std::stringstream consumer; + new CamSwitcher(objects::CAM_SWITCHER, pwrSwitch, pcdu::PDU2_CH8_PAYLOAD_CAMERA); #if OBSW_ADD_PLOC_MPSOC == 1 consumer << "0x" << std::hex << objects::PLOC_MPSOC_HANDLER; auto gpioConfigMPSoC = new GpiodRegularByLineName(q7s::gpioNames::ENABLE_MPSOC_UART, diff --git a/bsp_q7s/core/ObjectFactory.h b/bsp_q7s/core/ObjectFactory.h index 3737db92..40a4e2ed 100644 --- a/bsp_q7s/core/ObjectFactory.h +++ b/bsp_q7s/core/ObjectFactory.h @@ -38,7 +38,7 @@ void createBpxBatteryComponent(); void createStrComponents(PowerSwitchIF* pwrSwitcher); void createSolarArrayDeploymentComponents(PowerSwitchIF& pwrSwitcher, GpioIF& gpioIF); void createSyrlinksComponents(PowerSwitchIF* pwrSwitcher); -void createPayloadComponents(LinuxLibgpioIF* gpioComIF); +void createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF& pwrSwitcher); void createReactionWheelComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF* pwrSwitcher); ReturnValue_t createCcsdsComponents(LinuxLibgpioIF* gpioComIF, CcsdsIpCoreHandler** ipCoreHandler); void createMiscComponents(); diff --git a/bsp_q7s/fmObjectFactory.cpp b/bsp_q7s/fmObjectFactory.cpp index ac5037ec..6ac2498a 100644 --- a/bsp_q7s/fmObjectFactory.cpp +++ b/bsp_q7s/fmObjectFactory.cpp @@ -49,7 +49,7 @@ void ObjectFactory::produce(void* args) { createSyrlinksComponents(pwrSwitcher); #endif /* OBSW_ADD_SYRLINKS == 1 */ createRtdComponents(q7s::SPI_DEFAULT_DEV, gpioComIF, pwrSwitcher, spiMainComIF); - createPayloadComponents(gpioComIF); + createPayloadComponents(gpioComIF, *pwrSwitcher); #if OBSW_ADD_MGT == 1 createImtqComponents(pwrSwitcher); @@ -67,7 +67,7 @@ void ObjectFactory::produce(void* args) { CcsdsIpCoreHandler* ipCoreHandler = nullptr; createCcsdsComponents(gpioComIF, &ipCoreHandler); #if OBSW_TM_TO_PTME == 1 - ObjectFactory::addTmtcIpCoresToFunnels(*ipCoreHandler, *pusFunnel, *cfdpFunnel); + addTmtcIpCoresToFunnels(*ipCoreHandler, *pusFunnel, *cfdpFunnel); #endif #endif /* OBSW_ADD_CCSDS_IP_CORES == 1 */ diff --git a/mission/system/objects/CamSwitcher.cpp b/mission/system/objects/CamSwitcher.cpp index 459065ce..b995e211 100644 --- a/mission/system/objects/CamSwitcher.cpp +++ b/mission/system/objects/CamSwitcher.cpp @@ -1,5 +1,5 @@ #include "CamSwitcher.h" -CamSwitcher::CamSwitcher(object_id_t objectId, PowerSwitchIF *pwrSwitcher, +CamSwitcher::CamSwitcher(object_id_t objectId, PowerSwitchIF &pwrSwitcher, power::Switch_t pwrSwitch) - : PowerSwitcherComponent(objectId, pwrSwitcher, pwrSwitch) {} + : PowerSwitcherComponent(objectId, &pwrSwitcher, pwrSwitch) {} diff --git a/mission/system/objects/CamSwitcher.h b/mission/system/objects/CamSwitcher.h index c762d5da..672b884b 100644 --- a/mission/system/objects/CamSwitcher.h +++ b/mission/system/objects/CamSwitcher.h @@ -5,7 +5,7 @@ class CamSwitcher : public PowerSwitcherComponent { public: - CamSwitcher(object_id_t objectId, PowerSwitchIF *pwrSwitcher, power::Switch_t pwrSwitch); + CamSwitcher(object_id_t objectId, PowerSwitchIF &pwrSwitcher, power::Switch_t pwrSwitch); private: }; From 09ccb5ddf723974d4590ccabcc74b151b041e487 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 13:50:18 +0100 Subject: [PATCH 057/176] re-enable wipe cmd --- .../PlocSupervisorDefinitions.h | 100 +++++++++--------- linux/devices/ploc/PlocSupervisorHandler.cpp | 46 ++++---- linux/devices/ploc/PlocSupervisorHandler.h | 2 +- linux/devices/ploc/PlocSupvUartMan.cpp | 2 +- 4 files changed, 75 insertions(+), 75 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 8a642647..6901d8fe 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -1116,6 +1116,56 @@ class WriteMemory : public TcBase { } }; +/** + * @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 */ @@ -1931,56 +1981,6 @@ class EnableNvms : public TcBase { } }; -/** - * @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 creates the space packet to enable the auto TM generation */ diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 86547b73..b6783449 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -417,10 +417,10 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d // result = returnvalue::OK; // break; // } - // case WIPE_MRAM: { - // result = prepareWipeMramCmd(commandData); - // break; - // } + case WIPE_MRAM: { + result = prepareWipeMramCmd(commandData); + break; + } // case FIRST_MRAM_DUMP: // case CONSECUTIVE_MRAM_DUMP: // result = prepareDumpMramCmd(commandData); @@ -562,7 +562,7 @@ ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::ite case SET_ADC_THRESHOLD: // case COPY_ADC_DATA_TO_MRAM: case RUN_AUTO_EM_TESTS: - // case WIPE_MRAM: + case WIPE_MRAM: case SET_GPIO: case FACTORY_RESET: case READ_GPIO: @@ -1725,6 +1725,24 @@ ReturnValue_t PlocSupervisorHandler::handleMramDumpFile(DeviceCommandId_t id) { 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]; } @@ -2013,24 +2031,6 @@ uint32_t PlocSupervisorHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t mod // return result; // } -// 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; diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 9480667c..174ffa9e 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -285,7 +285,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t prepareSetAdcWindowAndStrideCmd(const uint8_t* commandData); ReturnValue_t prepareSetAdcThresholdCmd(const uint8_t* commandData); ReturnValue_t prepareRunAutoEmTest(const uint8_t* commandData); - // ReturnValue_t prepareWipeMramCmd(const uint8_t* commandData); + ReturnValue_t prepareWipeMramCmd(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); diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index d0c96e93..3bb6e764 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -417,7 +417,7 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { return result; } result = handlePacketTransmissionNoReply(packet); - //result = encodeAndSendPacket(packet.getFullPacket(), packet.getFullPacketLen()); + // result = encodeAndSendPacket(packet.getFullPacket(), packet.getFullPacketLen()); if (result != returnvalue::OK) { triggerEvent(WRITE_MEMORY_FAILED, buildProgParams1(progPercent, update.sequenceCount), update.bytesWritten); From 07d93b6b671f97bf189719abe619c0af75dded83 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 14:08:44 +0100 Subject: [PATCH 058/176] schedule PL components differently --- bsp_q7s/core/InitMission.cpp | 22 +++++++++---------- linux/InitMission.cpp | 13 +++++++++++ linux/InitMission.h | 4 +++- .../pollingSequenceFactory.cpp | 20 ----------------- 4 files changed, 26 insertions(+), 33 deletions(-) diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index 9740912a..bbeaded8 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -280,19 +280,9 @@ void initmission::initTasks() { PeriodicTaskIF* plTask = factory->createPeriodicTask( "PL_TASK", 25, 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::addMpsocSupvHandlers(plTask); + plTask->addComponent(objects::CAM_SWITCHER); -#if OBSW_TEST_CCSDS_BRIDGE == 1 - PeriodicTaskIF* ptmeTestTask = factory->createPeriodicTask( - "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); - } -#endif #if OBSW_ADD_SCEX_DEVICE == 1 PeriodicTaskIF* scexDevHandler; PeriodicTaskIF* scexReaderTask; @@ -305,6 +295,14 @@ void initmission::initTasks() { createPstTasks(*factory, missedDeadlineFunc, pstTasks); #if OBSW_ADD_TEST_CODE == 1 +#if OBSW_TEST_CCSDS_BRIDGE == 1 + PeriodicTaskIF* ptmeTestTask = factory->createPeriodicTask( + "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); + } +#endif std::vector testTasks; createTestTasks(*factory, missedDeadlineFunc, testTasks); #endif diff --git a/linux/InitMission.cpp b/linux/InitMission.cpp index eb8f677a..b433e4aa 100644 --- a/linux/InitMission.cpp +++ b/linux/InitMission.cpp @@ -45,3 +45,16 @@ void scheduling::schedulingScex(TaskFactory& factory, PeriodicTaskIF*& scexDevHa printAddObjectError("SCEX_UART_READER", objects::SCEX_UART_READER); } } + +void scheduling::addMpsocSupvHandlers(PeriodicTaskIF* plTask) { + 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_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); +} diff --git a/linux/InitMission.h b/linux/InitMission.h index e5a3afff..dd809ff7 100644 --- a/linux/InitMission.h +++ b/linux/InitMission.h @@ -4,4 +4,6 @@ namespace scheduling { void schedulingScex(TaskFactory& factory, PeriodicTaskIF*& scexDevHandler, PeriodicTaskIF*& scexReaderTask); -} +void addMpsocSupvHandlers(PeriodicTaskIF* task); + +} // namespace scheduling diff --git a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index f0a1c2fb..e7f753bd 100644 --- a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -461,26 +461,6 @@ ReturnValue_t pst::pstUart(FixedTimeslotTaskIF *thisSequence) { // Length of a communication cycle uint32_t length = thisSequence->getPeriodMs(); static_cast(length); -#if OBSW_ADD_PLOC_MPSOC == 1 - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::PLOC_MEMORY_DUMPER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); -#endif - -#if OBSW_ADD_PLOC_SUPERVISOR == 1 - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.2, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); -#endif #if OBSW_ADD_SYRLINKS == 1 thisSequence->addSlot(objects::SYRLINKS_HK_HANDLER, length * 0, From 76ca81b99747d840c45bbe1cb18f2b13e13bfc31 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 14:12:09 +0100 Subject: [PATCH 059/176] wrap in preproc defines --- linux/InitMission.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/linux/InitMission.cpp b/linux/InitMission.cpp index b433e4aa..5bc8698c 100644 --- a/linux/InitMission.cpp +++ b/linux/InitMission.cpp @@ -47,14 +47,19 @@ 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); +#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); +#endif } From 4c0bf18268ed9e5b6b871ebc47773b5d522df7ab Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 14:18:58 +0100 Subject: [PATCH 060/176] fix for object IDs --- common/config/eive/objects.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/common/config/eive/objects.h b/common/config/eive/objects.h index f0c06916..5b9ec8a0 100644 --- a/common/config/eive/objects.h +++ b/common/config/eive/objects.h @@ -131,11 +131,11 @@ enum commonObjects : uint32_t { ACS_SUBSYSTEM = 0x73010001, PL_SUBSYSTEM = 0x73010002, EIVE_SYSTEM = 0x73010000, - CFDP_HANDLER = 0x73000005, - CFDP_DISTRIBUTOR = 0x73000006, TM_FUNNEL = 0x73000100, PUS_TM_FUNNEL = 0x73000101, CFDP_TM_FUNNEL = 0x73000102, + CFDP_HANDLER = 0x73000205, + CFDP_DISTRIBUTOR = 0x73000206, }; } From f90120191f6544d2e58a01588fe9468e7c41f414 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 15:12:50 +0100 Subject: [PATCH 061/176] pl ss fixes --- fsfw | 2 +- mission/system/tree/payloadModeTree.cpp | 41 +++++++++++++------------ mission/system/tree/util.cpp | 6 ++-- 3 files changed, 27 insertions(+), 22 deletions(-) diff --git a/fsfw b/fsfw index 0e8f5ddd..530a261e 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 0e8f5ddd26d586dd40e69f52aef1a63c0d5a9da6 +Subproject commit 530a261e142ae4ab2c7726303e4d571d03200e47 diff --git a/mission/system/tree/payloadModeTree.cpp b/mission/system/tree/payloadModeTree.cpp index 89286947..ea339b74 100644 --- a/mission/system/tree/payloadModeTree.cpp +++ b/mission/system/tree/payloadModeTree.cpp @@ -25,31 +25,31 @@ static const auto OFF = HasModesIF::MODE_OFF; static const auto ON = HasModesIF::MODE_ON; static const auto NML = DeviceHandlerIF::MODE_NORMAL; -auto PL_SEQUENCE_OFF = std::make_pair(OFF << 24, FixedArrayList()); +auto PL_SEQUENCE_OFF = std::make_pair(OFF << 24, FixedArrayList()); auto PL_TABLE_OFF_TGT = std::make_pair((OFF << 24) | 1, FixedArrayList()); auto PL_TABLE_OFF_TRANS_0 = std::make_pair((OFF << 24) | 2, FixedArrayList()); auto PL_TABLE_OFF_TRANS_1 = std::make_pair((OFF << 24) | 3, FixedArrayList()); auto PL_SEQUENCE_MPSOC_STREAM = - std::make_pair(payload::Modes::MPSOC_STREAM << 24, FixedArrayList()); + std::make_pair(payload::Modes::MPSOC_STREAM << 24, FixedArrayList()); auto PL_TABLE_MPSOC_STREAM_TGT = - std::make_pair((payload::Modes::MPSOC_STREAM << 24) | 1, FixedArrayList()); + std::make_pair((payload::Modes::MPSOC_STREAM << 24) | 1, FixedArrayList()); auto PL_TABLE_MPSOC_STREAM_TRANS_0 = - std::make_pair((payload::Modes::MPSOC_STREAM << 24) | 2, FixedArrayList()); + std::make_pair((payload::Modes::MPSOC_STREAM << 24) | 2, FixedArrayList()); auto PL_TABLE_MPSOC_STREAM_TRANS_1 = - std::make_pair((payload::Modes::MPSOC_STREAM << 24) | 3, FixedArrayList()); + std::make_pair((payload::Modes::MPSOC_STREAM << 24) | 3, FixedArrayList()); auto PL_SEQUENCE_CAM_STREAM = - std::make_pair(payload::Modes::CAM_STREAM << 24, FixedArrayList()); + std::make_pair(payload::Modes::CAM_STREAM << 24, FixedArrayList()); auto PL_TABLE_CAM_STREAM_TGT = std::make_pair((payload::Modes::CAM_STREAM << 24) | 1, FixedArrayList()); auto PL_TABLE_CAM_STREAM_TRANS_0 = - std::make_pair((payload::Modes::CAM_STREAM << 24) | 2, FixedArrayList()); + std::make_pair((payload::Modes::CAM_STREAM << 24) | 2, FixedArrayList()); auto PL_TABLE_CAM_STREAM_TRANS_1 = - std::make_pair((payload::Modes::CAM_STREAM << 24) | 3, FixedArrayList()); + std::make_pair((payload::Modes::CAM_STREAM << 24) | 3, FixedArrayList()); auto PL_SEQUENCE_SUPV_ONLY = - std::make_pair(payload::Modes::SUPV_ONLY << 24, FixedArrayList()); + std::make_pair(payload::Modes::SUPV_ONLY << 24, FixedArrayList()); auto PL_TABLE_SUPV_ONLY_TGT = std::make_pair((payload::Modes::SUPV_ONLY << 24) | 1, FixedArrayList()); auto PL_TABLE_SUPV_ONLY_TRANS_0 = @@ -67,7 +67,7 @@ auto PL_TABLE_EARTH_OBSV_TRANS_1 = std::make_pair((payload::Modes::EARTH_OBSV << 24) | 3, FixedArrayList()); auto PL_SEQUENCE_SCEX = - std::make_pair(payload::Modes::SCEX << 24, FixedArrayList()); + std::make_pair(payload::Modes::SCEX << 24, FixedArrayList()); auto PL_TABLE_SCEX_TGT = std::make_pair((payload::Modes::SCEX << 24) | 1, FixedArrayList()); auto PL_TABLE_SCEX_TRANS_0 = @@ -165,13 +165,13 @@ void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh) { // Build MPSoC stream transition 0 iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); iht(objects::SCEX, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); - iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_MPSOC_STREAM_TGT.second); + iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); check(ss->addTable( TableEntry(PL_TABLE_MPSOC_STREAM_TRANS_0.first, &PL_TABLE_MPSOC_STREAM_TRANS_0.second)), ctxc); // Build MPSoC stream transition 1 - iht(objects::PLOC_MPSOC_HANDLER, NML, 0, PL_TABLE_MPSOC_STREAM_TGT.second); + iht(objects::PLOC_MPSOC_HANDLER, NML, 0, PL_TABLE_MPSOC_STREAM_TRANS_1.second); check(ss->addTable( TableEntry(PL_TABLE_MPSOC_STREAM_TRANS_1.first, &PL_TABLE_MPSOC_STREAM_TRANS_1.second)), ctxc); @@ -186,7 +186,7 @@ void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh) { } void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh) { - std::string context = "satsystem::payload::initPlCamSequence"; + std::string context = "satsystem::payload::initPlCamStreamSequence"; auto ctxc = context.c_str(); // Insert Helper Table auto iht = [&](object_id_t obj, Mode_t mode, Submode_t submode, @@ -214,17 +214,17 @@ void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh) { // Build CAM transition 0 // PLOC is actively commanded off here - iht(objects::PLOC_MPSOC_HANDLER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); - iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); - iht(objects::SCEX, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); + iht(objects::PLOC_MPSOC_HANDLER, OFF, 0, PL_TABLE_CAM_STREAM_TRANS_0.second); + iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_CAM_STREAM_TRANS_0.second); + iht(objects::SCEX, OFF, 0, PL_TABLE_CAM_STREAM_TRANS_0.second); check(ss->addTable( - TableEntry(PL_TABLE_MPSOC_STREAM_TRANS_0.first, &PL_TABLE_MPSOC_STREAM_TRANS_0.second)), + TableEntry(PL_TABLE_CAM_STREAM_TRANS_0.first, &PL_TABLE_CAM_STREAM_TRANS_0.second)), ctxc); // Build CAM transition 1 - iht(objects::PLOC_SUPERVISOR_HANDLER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_1.second); + iht(objects::PLOC_SUPERVISOR_HANDLER, OFF, 0, PL_TABLE_CAM_STREAM_TRANS_1.second); check(ss->addTable( - TableEntry(PL_TABLE_MPSOC_STREAM_TRANS_1.first, &PL_TABLE_MPSOC_STREAM_TRANS_1.second)), + TableEntry(PL_TABLE_CAM_STREAM_TRANS_1.first, &PL_TABLE_CAM_STREAM_TRANS_1.second)), ctxc); // Build CAM stream sequence @@ -270,6 +270,9 @@ void initPlSpvSequence(Subsystem* ss, ModeListEntry& eh) { // Build Payload Supervisor Only transition 1 iht(objects::PLOC_MPSOC_HANDLER, OFF, 0, PL_TABLE_SUPV_ONLY_TRANS_1.second); + check(ss->addTable( + TableEntry(PL_TABLE_SUPV_ONLY_TRANS_1.first, &PL_TABLE_SUPV_ONLY_TRANS_1.second)), + ctxc); // Build Payload Supervisor Only Sequence ihs(PL_SEQUENCE_SUPV_ONLY.second, PL_TABLE_SUPV_ONLY_TGT.first, 0, true); diff --git a/mission/system/tree/util.cpp b/mission/system/tree/util.cpp index 92a752e7..935e9d79 100644 --- a/mission/system/tree/util.cpp +++ b/mission/system/tree/util.cpp @@ -6,10 +6,12 @@ void subsystem::checkInsert(ReturnValue_t result, const char* ctx) { if (result != returnvalue::OK) { sif::warning << "satsystem::checkInsert: Insertion failed at " << ctx; - if (result == mapdefs::KEY_ALREADY_EXISTS) { + if (result == containers::KEY_ALREADY_EXISTS) { sif::warning << ": Key already exists" << std::endl; - } else if (result == mapdefs::MAP_FULL) { + } else if (result == containers::MAP_FULL) { sif::warning << ": Map full" << std::endl; + } else if (result == containers::LIST_FULL) { + sif::warning << ": List full" << std::endl; } else { sif::warning << std::endl; } From d690a54005d5bf93c14e330eeba28f5d68667899 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 15:39:08 +0100 Subject: [PATCH 062/176] connect payload children to subsystem --- bsp_q7s/core/ObjectFactory.cpp | 22 +++-- fsfw | 2 +- linux/ObjectFactory.cpp | 2 + mission/system/tree/payloadModeTree.cpp | 109 ++++++++++++------------ mission/system/tree/payloadModeTree.h | 7 +- 5 files changed, 78 insertions(+), 64 deletions(-) diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index 13998027..bc46efb5 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -1,5 +1,6 @@ #include "ObjectFactory.h" +#include #include #include "OBSWConfig.h" @@ -47,6 +48,7 @@ #include "mission/system/objects/RwAssembly.h" #include "mission/system/objects/TcsBoardAssembly.h" #include "mission/system/tree/acsModeTree.h" +#include "mission/system/tree/payloadModeTree.h" #include "tmtc/pusIds.h" #if OBSW_TEST_LIBGPIOD == 1 #include "linux/boardtest/LibgpiodTest.h" @@ -588,7 +590,10 @@ void ObjectFactory::createSyrlinksComponents(PowerSwitchIF* pwrSwitcher) { void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF& pwrSwitch) { using namespace gpio; std::stringstream consumer; - new CamSwitcher(objects::CAM_SWITCHER, pwrSwitch, pcdu::PDU2_CH8_PAYLOAD_CAMERA); + 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, @@ -601,9 +606,10 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwit 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, gpioComIF), - objects::PLOC_SUPERVISOR_HANDLER); + auto* mpsocHandler = new PlocMPSoCHandler( + objects::PLOC_MPSOC_HANDLER, objects::UART_COM_IF, mpsocCookie, plocMpsocHelper, + Gpio(gpioIds::ENABLE_MPSOC_UART, gpioComIF), objects::PLOC_SUPERVISOR_HANDLER); + mpsocHandler->connectModeTreeParent(satsystem::pl::SUBSYSTEM); #endif /* OBSW_ADD_PLOC_MPSOC == 1 */ #if OBSW_ADD_PLOC_SUPERVISOR == 1 consumer << "0x" << std::hex << objects::PLOC_SUPERVISOR_HANDLER; @@ -617,9 +623,10 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwit uart::PLOC_SUPV_BAUD, supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL); supervisorCookie->setNoFixedSizeReply(); auto supvHelper = new PlocSupvHelper(objects::PLOC_SUPERVISOR_HELPER); - new PlocSupervisorHandler(objects::PLOC_SUPERVISOR_HANDLER, objects::UART_COM_IF, - supervisorCookie, Gpio(gpioIds::ENABLE_SUPV_UART, gpioComIF), - pcdu::PDU1_CH6_PLOC_12V, supvHelper); + 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); + supvHandler->connectModeTreeParent(satsystem::pl::SUBSYSTEM); #endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */ static_cast(consumer); } @@ -880,6 +887,7 @@ void ObjectFactory::createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* plPcduHandler->setToGoToNormalModeImmediately(true); plPcduHandler->enablePeriodicPrintout(true, 10); #endif + plPcduHandler->connectModeTreeParent(satsystem::pl::SUBSYSTEM); } void ObjectFactory::createTestComponents(LinuxLibgpioIF* gpioComIF) { diff --git a/fsfw b/fsfw index 530a261e..177c39dd 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 530a261e142ae4ab2c7726303e4d571d03200e47 +Subproject commit 177c39dd53198a1b05e2f40fc3c5e88e7f7c2e0b diff --git a/linux/ObjectFactory.cpp b/linux/ObjectFactory.cpp index 24bb6254..2fe31372 100644 --- a/linux/ObjectFactory.cpp +++ b/linux/ObjectFactory.cpp @@ -27,6 +27,7 @@ #include "mission/system/objects/SusAssembly.h" #include "mission/system/objects/TcsBoardAssembly.h" #include "mission/system/tree/acsModeTree.h" +#include "mission/system/tree/payloadModeTree.h" void ObjectFactory::createSunSensorComponents(GpioIF* gpioComIF, SpiComIF* spiComIF, PowerSwitchIF* pwrSwitcher, std::string spiDev) { @@ -336,6 +337,7 @@ void ObjectFactory::createScexComponents(std::string uartDev, PowerSwitchIF* pwr if (switchId) { scexHandler->setPowerSwitcher(*pwrSwitcher, switchId.value()); } + scexHandler->connectModeTreeParent(satsystem::pl::SUBSYSTEM); } void ObjectFactory::createThermalController() { diff --git a/mission/system/tree/payloadModeTree.cpp b/mission/system/tree/payloadModeTree.cpp index ea339b74..6cbc4004 100644 --- a/mission/system/tree/payloadModeTree.cpp +++ b/mission/system/tree/payloadModeTree.cpp @@ -12,14 +12,16 @@ #include "util.h" namespace { -void initOffSequence(Subsystem* ss, ModeListEntry& eh); -void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh); -void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh); -void initPlSpvSequence(Subsystem* ss, ModeListEntry& eh); -void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh); -void initScexSequence(Subsystem* ss, ModeListEntry& eh); +void initOffSequence(Subsystem& ss, ModeListEntry& eh); +void initPlMpsocStreamSequence(Subsystem& ss, ModeListEntry& eh); +void initPlCamStreamSequence(Subsystem& ss, ModeListEntry& eh); +void initPlSpvSequence(Subsystem& ss, ModeListEntry& eh); +void initEarthObsvSequence(Subsystem& ss, ModeListEntry& eh); +void initScexSequence(Subsystem& ss, ModeListEntry& eh); } // namespace +Subsystem satsystem::pl::SUBSYSTEM = Subsystem(objects::PL_SUBSYSTEM, 12, 24); + const auto check = subsystem::checkInsert; static const auto OFF = HasModesIF::MODE_OFF; static const auto ON = HasModesIF::MODE_ON; @@ -75,19 +77,18 @@ auto PL_TABLE_SCEX_TRANS_0 = void satsystem::pl::init() { ModeListEntry entry; - Subsystem* plSubsystem = new Subsystem(objects::PL_SUBSYSTEM, 12, 24); - initOffSequence(plSubsystem, entry); - initPlMpsocStreamSequence(plSubsystem, entry); - initPlCamStreamSequence(plSubsystem, entry); - initPlSpvSequence(plSubsystem, entry); - initEarthObsvSequence(plSubsystem, entry); - initScexSequence(plSubsystem, entry); - plSubsystem->setInitialMode(OFF); + initOffSequence(SUBSYSTEM, entry); + initPlMpsocStreamSequence(SUBSYSTEM, entry); + initPlCamStreamSequence(SUBSYSTEM, entry); + initPlSpvSequence(SUBSYSTEM, entry); + initEarthObsvSequence(SUBSYSTEM, entry); + initScexSequence(SUBSYSTEM, entry); + SUBSYSTEM.setInitialMode(OFF); } namespace { -void initOffSequence(Subsystem* ss, ModeListEntry& eh) { +void initOffSequence(Subsystem& ss, ModeListEntry& eh) { std::string context = "satsystem::payload::buildOffSequence"; auto ctxc = context.c_str(); // Insert Helper Table @@ -108,29 +109,29 @@ void initOffSequence(Subsystem* ss, ModeListEntry& eh) { }; // Build OFF target. Is empty - check(ss->addTable(TableEntry(PL_TABLE_OFF_TGT.first, &PL_TABLE_OFF_TGT.second)), ctxc); + check(ss.addTable(TableEntry(PL_TABLE_OFF_TGT.first, &PL_TABLE_OFF_TGT.second)), ctxc); // Build OFF transition 0 iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_OFF_TRANS_0.second); iht(objects::SCEX, OFF, 0, PL_TABLE_OFF_TRANS_0.second); iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_OFF_TRANS_0.second); iht(objects::PLOC_MPSOC_HANDLER, OFF, 0, PL_TABLE_OFF_TRANS_0.second); - check(ss->addTable(TableEntry(PL_TABLE_OFF_TRANS_0.first, &PL_TABLE_OFF_TRANS_0.second)), ctxc); + check(ss.addTable(TableEntry(PL_TABLE_OFF_TRANS_0.first, &PL_TABLE_OFF_TRANS_0.second)), ctxc); // Build OFF transition 1 iht(objects::PLOC_SUPERVISOR_HANDLER, OFF, 0, PL_TABLE_OFF_TRANS_1.second); - check(ss->addTable(TableEntry(PL_TABLE_OFF_TRANS_1.first, &PL_TABLE_OFF_TRANS_1.second)), ctxc); + check(ss.addTable(TableEntry(PL_TABLE_OFF_TRANS_1.first, &PL_TABLE_OFF_TRANS_1.second)), ctxc); // Build OFF sequence ihs(PL_SEQUENCE_OFF.second, PL_TABLE_OFF_TGT.first, 0, false); ihs(PL_SEQUENCE_OFF.second, PL_TABLE_OFF_TRANS_0.first, 0, false); ihs(PL_SEQUENCE_OFF.second, PL_TABLE_OFF_TRANS_1.first, 0, false); - check(ss->addSequence( + check(ss.addSequence( SequenceEntry(PL_SEQUENCE_OFF.first, &PL_SEQUENCE_OFF.second, PL_SEQUENCE_OFF.first)), ctxc); } -void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh) { +void initPlMpsocStreamSequence(Subsystem& ss, ModeListEntry& eh) { std::string context = "satsystem::payload::initPlMpsocStreamSequence"; auto ctxc = context.c_str(); // Insert Helper Table @@ -158,21 +159,20 @@ void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh) { iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_MPSOC_STREAM_TGT.second); iht(objects::PLOC_MPSOC_HANDLER, NML, 0, PL_TABLE_MPSOC_STREAM_TGT.second); iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_MPSOC_STREAM_TGT.second); - check( - ss->addTable(TableEntry(PL_TABLE_MPSOC_STREAM_TGT.first, &PL_TABLE_MPSOC_STREAM_TGT.second)), - ctxc); + check(ss.addTable(TableEntry(PL_TABLE_MPSOC_STREAM_TGT.first, &PL_TABLE_MPSOC_STREAM_TGT.second)), + ctxc); // Build MPSoC stream transition 0 iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); iht(objects::SCEX, OFF, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_MPSOC_STREAM_TRANS_0.second); - check(ss->addTable( + check(ss.addTable( TableEntry(PL_TABLE_MPSOC_STREAM_TRANS_0.first, &PL_TABLE_MPSOC_STREAM_TRANS_0.second)), ctxc); // Build MPSoC stream transition 1 iht(objects::PLOC_MPSOC_HANDLER, NML, 0, PL_TABLE_MPSOC_STREAM_TRANS_1.second); - check(ss->addTable( + check(ss.addTable( TableEntry(PL_TABLE_MPSOC_STREAM_TRANS_1.first, &PL_TABLE_MPSOC_STREAM_TRANS_1.second)), ctxc); @@ -180,12 +180,12 @@ void initPlMpsocStreamSequence(Subsystem* ss, ModeListEntry& eh) { ihs(PL_SEQUENCE_MPSOC_STREAM.second, PL_TABLE_MPSOC_STREAM_TGT.first, 0, true); ihs(PL_SEQUENCE_MPSOC_STREAM.second, PL_TABLE_MPSOC_STREAM_TRANS_0.first, 0, true); ihs(PL_SEQUENCE_MPSOC_STREAM.second, PL_TABLE_MPSOC_STREAM_TRANS_1.first, 0, false); - check(ss->addSequence(SequenceEntry(PL_SEQUENCE_MPSOC_STREAM.first, - &PL_SEQUENCE_MPSOC_STREAM.second, PL_SEQUENCE_OFF.first)), + check(ss.addSequence(SequenceEntry(PL_SEQUENCE_MPSOC_STREAM.first, + &PL_SEQUENCE_MPSOC_STREAM.second, PL_SEQUENCE_OFF.first)), ctxc); } -void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh) { +void initPlCamStreamSequence(Subsystem& ss, ModeListEntry& eh) { std::string context = "satsystem::payload::initPlCamStreamSequence"; auto ctxc = context.c_str(); // Insert Helper Table @@ -209,7 +209,7 @@ void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh) { // Only check that the PL PCDU is on for now. It might later become necessary to switch on // the PLOC, so we ignore its state. iht(objects::PLPCDU_HANDLER, NML, plpcdu::ALL_ON_SUBMODE, PL_TABLE_CAM_STREAM_TGT.second); - check(ss->addTable(TableEntry(PL_TABLE_CAM_STREAM_TGT.first, &PL_TABLE_CAM_STREAM_TGT.second)), + check(ss.addTable(TableEntry(PL_TABLE_CAM_STREAM_TGT.first, &PL_TABLE_CAM_STREAM_TGT.second)), ctxc); // Build CAM transition 0 @@ -217,13 +217,13 @@ void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh) { iht(objects::PLOC_MPSOC_HANDLER, OFF, 0, PL_TABLE_CAM_STREAM_TRANS_0.second); iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_CAM_STREAM_TRANS_0.second); iht(objects::SCEX, OFF, 0, PL_TABLE_CAM_STREAM_TRANS_0.second); - check(ss->addTable( + check(ss.addTable( TableEntry(PL_TABLE_CAM_STREAM_TRANS_0.first, &PL_TABLE_CAM_STREAM_TRANS_0.second)), ctxc); // Build CAM transition 1 iht(objects::PLOC_SUPERVISOR_HANDLER, OFF, 0, PL_TABLE_CAM_STREAM_TRANS_1.second); - check(ss->addTable( + check(ss.addTable( TableEntry(PL_TABLE_CAM_STREAM_TRANS_1.first, &PL_TABLE_CAM_STREAM_TRANS_1.second)), ctxc); @@ -231,12 +231,12 @@ void initPlCamStreamSequence(Subsystem* ss, ModeListEntry& eh) { ihs(PL_SEQUENCE_CAM_STREAM.second, PL_TABLE_CAM_STREAM_TGT.first, 0, true); ihs(PL_SEQUENCE_CAM_STREAM.second, PL_TABLE_CAM_STREAM_TRANS_0.first, 0, true); ihs(PL_SEQUENCE_CAM_STREAM.second, PL_TABLE_CAM_STREAM_TRANS_1.first, 0, false); - check(ss->addSequence(SequenceEntry(PL_SEQUENCE_CAM_STREAM.first, &PL_SEQUENCE_CAM_STREAM.second, - PL_SEQUENCE_OFF.first)), + check(ss.addSequence(SequenceEntry(PL_SEQUENCE_CAM_STREAM.first, &PL_SEQUENCE_CAM_STREAM.second, + PL_SEQUENCE_OFF.first)), ctxc); } -void initPlSpvSequence(Subsystem* ss, ModeListEntry& eh) { +void initPlSpvSequence(Subsystem& ss, ModeListEntry& eh) { std::string context = "satsystem::payload::initPlSupvSequence"; auto ctxc = context.c_str(); // Insert Helper Table @@ -258,32 +258,32 @@ void initPlSpvSequence(Subsystem* ss, ModeListEntry& eh) { // Build Payload Supervisor Only target iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_SUPV_ONLY_TGT.second); - check(ss->addTable(TableEntry(PL_TABLE_SUPV_ONLY_TGT.first, &PL_TABLE_SUPV_ONLY_TGT.second)), + check(ss.addTable(TableEntry(PL_TABLE_SUPV_ONLY_TGT.first, &PL_TABLE_SUPV_ONLY_TGT.second)), ctxc); // Build Payload Supervisor Only transition 0 iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_SUPV_ONLY_TRANS_0.second); iht(objects::CAM_SWITCHER, OFF, 0, PL_TABLE_SUPV_ONLY_TRANS_0.second); - check(ss->addTable( - TableEntry(PL_TABLE_SUPV_ONLY_TRANS_0.first, &PL_TABLE_SUPV_ONLY_TRANS_0.second)), - ctxc); + check( + ss.addTable(TableEntry(PL_TABLE_SUPV_ONLY_TRANS_0.first, &PL_TABLE_SUPV_ONLY_TRANS_0.second)), + ctxc); // Build Payload Supervisor Only transition 1 iht(objects::PLOC_MPSOC_HANDLER, OFF, 0, PL_TABLE_SUPV_ONLY_TRANS_1.second); - check(ss->addTable( - TableEntry(PL_TABLE_SUPV_ONLY_TRANS_1.first, &PL_TABLE_SUPV_ONLY_TRANS_1.second)), - ctxc); + check( + ss.addTable(TableEntry(PL_TABLE_SUPV_ONLY_TRANS_1.first, &PL_TABLE_SUPV_ONLY_TRANS_1.second)), + ctxc); // Build Payload Supervisor Only Sequence ihs(PL_SEQUENCE_SUPV_ONLY.second, PL_TABLE_SUPV_ONLY_TGT.first, 0, true); ihs(PL_SEQUENCE_SUPV_ONLY.second, PL_TABLE_SUPV_ONLY_TRANS_0.first, 0, true); ihs(PL_SEQUENCE_SUPV_ONLY.second, PL_TABLE_SUPV_ONLY_TRANS_1.first, 0, false); - check(ss->addSequence(SequenceEntry(PL_SEQUENCE_SUPV_ONLY.first, &PL_SEQUENCE_SUPV_ONLY.second, - PL_SEQUENCE_OFF.first)), + check(ss.addSequence(SequenceEntry(PL_SEQUENCE_SUPV_ONLY.first, &PL_SEQUENCE_SUPV_ONLY.second, + PL_SEQUENCE_OFF.first)), ctxc); } -void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh) { +void initEarthObsvSequence(Subsystem& ss, ModeListEntry& eh) { std::string context = "satsystem::payload::initEarthObsvSequence"; auto ctxc = context.c_str(); // Insert Helper Table @@ -308,32 +308,32 @@ void initEarthObsvSequence(Subsystem* ss, ModeListEntry& eh) { iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_EARTH_OBSV_TGT.second); iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_EARTH_OBSV_TGT.second); iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_EARTH_OBSV_TGT.second); - check(ss->addTable(TableEntry(PL_TABLE_EARTH_OBSV_TGT.first, &PL_TABLE_EARTH_OBSV_TGT.second)), + check(ss.addTable(TableEntry(PL_TABLE_EARTH_OBSV_TGT.first, &PL_TABLE_EARTH_OBSV_TGT.second)), ctxc); // Build Earth Observation transition 0 iht(objects::PLOC_SUPERVISOR_HANDLER, NML, 0, PL_TABLE_EARTH_OBSV_TRANS_0.second); iht(objects::CAM_SWITCHER, ON, 0, PL_TABLE_EARTH_OBSV_TRANS_0.second); iht(objects::PLPCDU_HANDLER, OFF, 0, PL_TABLE_EARTH_OBSV_TRANS_0.second); - check(ss->addTable( + check(ss.addTable( TableEntry(PL_TABLE_EARTH_OBSV_TRANS_0.first, &PL_TABLE_EARTH_OBSV_TRANS_0.second)), ctxc); // Build Earth Observation transition 1 iht(objects::PLOC_MPSOC_HANDLER, NML, 0, PL_TABLE_CAM_STREAM_TRANS_1.second); - check(ss->addTable( + check(ss.addTable( TableEntry(PL_TABLE_EARTH_OBSV_TRANS_1.first, &PL_TABLE_EARTH_OBSV_TRANS_1.second)), ctxc); ihs(PL_SEQUENCE_EARTH_OBSV.second, PL_TABLE_EARTH_OBSV_TGT.first, 0, true); ihs(PL_SEQUENCE_EARTH_OBSV.second, PL_TABLE_EARTH_OBSV_TRANS_0.first, 0, true); ihs(PL_SEQUENCE_EARTH_OBSV.second, PL_TABLE_EARTH_OBSV_TRANS_1.first, 0, false); - check(ss->addSequence(SequenceEntry(PL_SEQUENCE_EARTH_OBSV.first, &PL_SEQUENCE_EARTH_OBSV.second, - PL_SEQUENCE_OFF.first)), + check(ss.addSequence(SequenceEntry(PL_SEQUENCE_EARTH_OBSV.first, &PL_SEQUENCE_EARTH_OBSV.second, + PL_SEQUENCE_OFF.first)), ctxc); } -void initScexSequence(Subsystem* ss, ModeListEntry& eh) { +void initScexSequence(Subsystem& ss, ModeListEntry& eh) { std::string context = "satsystem::payload::initScexSequence"; auto ctxc = context.c_str(); // Insert Helper Table @@ -355,17 +355,16 @@ void initScexSequence(Subsystem* ss, ModeListEntry& eh) { // Build SCEX target iht(objects::SCEX, NML, 0, PL_TABLE_SCEX_TGT.second); - check(ss->addTable(TableEntry(PL_TABLE_EARTH_OBSV_TGT.first, &PL_TABLE_EARTH_OBSV_TGT.second)), - ctxc); + check(ss.addTable(TableEntry(PL_TABLE_SCEX_TGT.first, &PL_TABLE_SCEX_TGT.second)), ctxc); // Build SCEX transition 0 - iht(objects::SCEX, NML, 0, PL_TABLE_SCEX_TGT.second); - check(ss->addTable(TableEntry(PL_TABLE_SCEX_TRANS_0.first, &PL_TABLE_SCEX_TRANS_0.second)), ctxc); + iht(objects::SCEX, NML, 0, PL_TABLE_SCEX_TRANS_0.second); + check(ss.addTable(TableEntry(PL_TABLE_SCEX_TRANS_0.first, &PL_TABLE_SCEX_TRANS_0.second)), ctxc); // Build SCEX sequence ihs(PL_SEQUENCE_SCEX.second, PL_TABLE_SCEX_TGT.first, 0, true); ihs(PL_SEQUENCE_SCEX.second, PL_TABLE_SCEX_TRANS_0.first, 0, false); - check(ss->addSequence( + check(ss.addSequence( SequenceEntry(PL_SEQUENCE_SCEX.first, &PL_SEQUENCE_SCEX.second, PL_SEQUENCE_OFF.first)), ctxc); } diff --git a/mission/system/tree/payloadModeTree.h b/mission/system/tree/payloadModeTree.h index 738eb01c..d1eae4d7 100644 --- a/mission/system/tree/payloadModeTree.h +++ b/mission/system/tree/payloadModeTree.h @@ -1,11 +1,16 @@ #ifndef MISSION_SYSTEM_TREE_PAYLOADMODETREE_H_ #define MISSION_SYSTEM_TREE_PAYLOADMODETREE_H_ +#include + namespace satsystem { namespace pl { + +extern Subsystem SUBSYSTEM; + void init(); -} +} // namespace pl } // namespace satsystem From e7005c18a4a3d58c93590fb7c032ec9840cb4e5d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 15:58:48 +0100 Subject: [PATCH 063/176] bump fsfw --- fsfw | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fsfw b/fsfw index 177c39dd..194b3e10 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 177c39dd53198a1b05e2f40fc3c5e88e7f7c2e0b +Subproject commit 194b3e100a036b1fef22566693549b327d48c6a5 From 5ed0ade358447e54b9f3362258b8fb084fb5e6cb Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 16:23:51 +0100 Subject: [PATCH 064/176] bump fsfw --- fsfw | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fsfw b/fsfw index 194b3e10..2a203ae1 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 194b3e100a036b1fef22566693549b327d48c6a5 +Subproject commit 2a203ae13d0b872189c0a79147c92312a44c08b1 From ec7ce5ddb6b3b7d21e157c9316e42dbcbffc97d9 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 17:32:11 +0100 Subject: [PATCH 065/176] ploc components now compile for hosted (linux) --- CMakeLists.txt | 6 ++- bsp_hosted/ObjectFactory.cpp | 44 ++++++++++++++++++- bsp_linux_board/CMakeLists.txt | 1 + .../fsfwconfig/CMakeLists.txt | 0 .../fsfwconfig/FSFWConfig.h.in | 0 .../fsfwconfig/events/subsystemIdRanges.h | 0 .../fsfwconfig/events/translateEvents.cpp | 0 .../fsfwconfig/events/translateEvents.h | 0 .../fsfwconfig/ipc/MissionMessageTypes.cpp | 0 .../fsfwconfig/ipc/MissionMessageTypes.h | 0 .../fsfwconfig/objects/systemObjectList.h | 2 - .../fsfwconfig/objects/translateObjects.cpp | 0 .../fsfwconfig/objects/translateObjects.h | 0 .../pollingSequenceFactory.cpp | 0 .../pollingsequence/pollingSequenceFactory.h | 0 .../fsfwconfig/returnvalues/classIds.h | 0 bsp_q7s/core/ObjectFactory.cpp | 1 - common/config/devConf.h | 3 +- .../config}/devices/addresses.h | 0 common/config/eive/objects.h | 4 ++ fsfw | 2 +- linux/CMakeLists.txt | 1 - linux/InitMission.cpp | 1 + linux/ObjectFactory.cpp | 2 +- linux/boardtest/SpiTestClass.cpp | 28 +++++++----- linux/boardtest/UartTestClass.cpp | 3 +- linux/boardtest/UartTestClass.h | 2 +- linux/devices/ScexUartReader.cpp | 2 +- .../devicedefinitions/MPSoCReturnValuesIF.h | 1 + .../PlocSupervisorDefinitions.h | 4 +- linux/devices/ploc/PlocMPSoCHandler.cpp | 2 +- linux/devices/ploc/PlocMPSoCHandler.h | 5 ++- linux/devices/ploc/PlocMPSoCHelper.cpp | 2 +- linux/devices/ploc/PlocMPSoCHelper.h | 5 ++- linux/devices/ploc/PlocMemoryDumper.h | 7 ++- linux/devices/ploc/PlocSupervisorHandler.cpp | 4 +- linux/devices/ploc/PlocSupervisorHandler.h | 13 +++--- linux/devices/ploc/PlocSupvUartMan.cpp | 3 +- linux/devices/ploc/PlocSupvUartMan.h | 2 +- .../devices/startracker/ArcsecDatalinkLayer.h | 1 + .../devices/startracker/ArcsecJsonParamBase.h | 1 + .../startracker/StarTrackerHandler.cpp | 2 +- linux/devices/startracker/StrHelper.cpp | 2 +- linux/devices/startracker/StrHelper.h | 5 ++- linux/fsfwconfig/devices/addresses.cpp | 1 - 45 files changed, 116 insertions(+), 46 deletions(-) rename {linux => bsp_linux_board}/fsfwconfig/CMakeLists.txt (100%) rename {linux => bsp_linux_board}/fsfwconfig/FSFWConfig.h.in (100%) rename {linux => bsp_linux_board}/fsfwconfig/events/subsystemIdRanges.h (100%) rename {linux => bsp_linux_board}/fsfwconfig/events/translateEvents.cpp (100%) rename {linux => bsp_linux_board}/fsfwconfig/events/translateEvents.h (100%) rename {linux => bsp_linux_board}/fsfwconfig/ipc/MissionMessageTypes.cpp (100%) rename {linux => bsp_linux_board}/fsfwconfig/ipc/MissionMessageTypes.h (100%) rename {linux => bsp_linux_board}/fsfwconfig/objects/systemObjectList.h (96%) rename {linux => bsp_linux_board}/fsfwconfig/objects/translateObjects.cpp (100%) rename {linux => bsp_linux_board}/fsfwconfig/objects/translateObjects.h (100%) rename {linux => bsp_linux_board}/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp (100%) rename {linux => bsp_linux_board}/fsfwconfig/pollingsequence/pollingSequenceFactory.h (100%) rename {linux => bsp_linux_board}/fsfwconfig/returnvalues/classIds.h (100%) rename {linux/fsfwconfig => common/config}/devices/addresses.h (100%) delete mode 100644 linux/fsfwconfig/devices/addresses.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index 644b8bcd..f940ea0f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -233,7 +233,11 @@ set(LIB_ARCSEC_PATH ${THIRD_PARTY_FOLDER}/arcsec_star_tracker) set(LIB_JSON_PATH ${THIRD_PARTY_FOLDER}/json) set(FSFW_WARNING_SHADOW_LOCAL_GCC OFF) -set(EIVE_ADD_LINUX_FILES False) +set(EIVE_ADD_LINUX_FILES OFF) + +if(UNIX) + set(EIVE_ADD_LINUX_FILES ON) +endif() # Analyse different OS and architecture/target options, determine BSP_PATH, # display information about compiler etc. diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index a3c94fe1..7e7bda14 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -6,11 +6,13 @@ #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,6 +49,19 @@ #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; @@ -63,6 +78,33 @@ void ObjectFactory::produce(void* args) { CfdpTmFunnel* cfdpFunnel; ObjectFactory::produceGenericObjects(nullptr, &pusFunnel, &cfdpFunnel); + DummyGpioIF* dummyGpioIF = new DummyGpioIF(); + 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 = ""; + auto supervisorCookie = + new UartCookie(objects::PLOC_SUPERVISOR_HANDLER, plocSupvString, uart::PLOC_SUPV_BAUD, + supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL); + supervisorCookie->setNoFixedSizeReply(); + auto supvHelper = new PlocSupvHelper(objects::PLOC_SUPERVISOR_HELPER); + new PlocSupervisorHandler(objects::PLOC_SUPERVISOR_HANDLER, objects::PLOC_SUPERVISOR_HELPER, + 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(); diff --git a/bsp_linux_board/CMakeLists.txt b/bsp_linux_board/CMakeLists.txt index c1817ac1..39f06401 100644 --- a/bsp_linux_board/CMakeLists.txt +++ b/bsp_linux_board/CMakeLists.txt @@ -3,3 +3,4 @@ target_sources(${OBSW_NAME} PUBLIC InitMission.cpp main.cpp gpioInit.cpp add_subdirectory(boardconfig) add_subdirectory(boardtest) +add_subdirectory(fsfwconfig) diff --git a/linux/fsfwconfig/CMakeLists.txt b/bsp_linux_board/fsfwconfig/CMakeLists.txt similarity index 100% rename from linux/fsfwconfig/CMakeLists.txt rename to bsp_linux_board/fsfwconfig/CMakeLists.txt diff --git a/linux/fsfwconfig/FSFWConfig.h.in b/bsp_linux_board/fsfwconfig/FSFWConfig.h.in similarity index 100% rename from linux/fsfwconfig/FSFWConfig.h.in rename to bsp_linux_board/fsfwconfig/FSFWConfig.h.in diff --git a/linux/fsfwconfig/events/subsystemIdRanges.h b/bsp_linux_board/fsfwconfig/events/subsystemIdRanges.h similarity index 100% rename from linux/fsfwconfig/events/subsystemIdRanges.h rename to bsp_linux_board/fsfwconfig/events/subsystemIdRanges.h diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/bsp_linux_board/fsfwconfig/events/translateEvents.cpp similarity index 100% rename from linux/fsfwconfig/events/translateEvents.cpp rename to bsp_linux_board/fsfwconfig/events/translateEvents.cpp diff --git a/linux/fsfwconfig/events/translateEvents.h b/bsp_linux_board/fsfwconfig/events/translateEvents.h similarity index 100% rename from linux/fsfwconfig/events/translateEvents.h rename to bsp_linux_board/fsfwconfig/events/translateEvents.h diff --git a/linux/fsfwconfig/ipc/MissionMessageTypes.cpp b/bsp_linux_board/fsfwconfig/ipc/MissionMessageTypes.cpp similarity index 100% rename from linux/fsfwconfig/ipc/MissionMessageTypes.cpp rename to bsp_linux_board/fsfwconfig/ipc/MissionMessageTypes.cpp diff --git a/linux/fsfwconfig/ipc/MissionMessageTypes.h b/bsp_linux_board/fsfwconfig/ipc/MissionMessageTypes.h similarity index 100% rename from linux/fsfwconfig/ipc/MissionMessageTypes.h rename to bsp_linux_board/fsfwconfig/ipc/MissionMessageTypes.h diff --git a/linux/fsfwconfig/objects/systemObjectList.h b/bsp_linux_board/fsfwconfig/objects/systemObjectList.h similarity index 96% rename from linux/fsfwconfig/objects/systemObjectList.h rename to bsp_linux_board/fsfwconfig/objects/systemObjectList.h index dba8c630..8f36b013 100644 --- a/linux/fsfwconfig/objects/systemObjectList.h +++ b/bsp_linux_board/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/bsp_linux_board/fsfwconfig/objects/translateObjects.cpp similarity index 100% rename from linux/fsfwconfig/objects/translateObjects.cpp rename to bsp_linux_board/fsfwconfig/objects/translateObjects.cpp diff --git a/linux/fsfwconfig/objects/translateObjects.h b/bsp_linux_board/fsfwconfig/objects/translateObjects.h similarity index 100% rename from linux/fsfwconfig/objects/translateObjects.h rename to bsp_linux_board/fsfwconfig/objects/translateObjects.h diff --git a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/bsp_linux_board/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp similarity index 100% rename from linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp rename to bsp_linux_board/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp diff --git a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.h b/bsp_linux_board/fsfwconfig/pollingsequence/pollingSequenceFactory.h similarity index 100% rename from linux/fsfwconfig/pollingsequence/pollingSequenceFactory.h rename to bsp_linux_board/fsfwconfig/pollingsequence/pollingSequenceFactory.h diff --git a/linux/fsfwconfig/returnvalues/classIds.h b/bsp_linux_board/fsfwconfig/returnvalues/classIds.h similarity index 100% rename from linux/fsfwconfig/returnvalues/classIds.h rename to bsp_linux_board/fsfwconfig/returnvalues/classIds.h diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index bc46efb5..718594e1 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -593,7 +593,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, diff --git a/common/config/devConf.h b/common/config/devConf.h index 88e78e1e..5f8164f6 100644 --- a/common/config/devConf.h +++ b/common/config/devConf.h @@ -1,11 +1,12 @@ #ifndef COMMON_CONFIG_DEVCONF_H_ #define COMMON_CONFIG_DEVCONF_H_ +#include + #include #include "fsfw/timemanager/clockDefinitions.h" #include "fsfw_hal/linux/spi/spiDefinitions.h" -#include "fsfw_hal/linux/uart/UartCookie.h" /** * SPI configuration will be contained here to let the device handlers remain independent 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 5b9ec8a0..e5192a82 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/fsfw b/fsfw index 2a203ae1..39946bff 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 2a203ae13d0b872189c0a79147c92312a44c08b1 +Subproject commit 39946bff58db7c5ac9016ca3156abb059560d9cb diff --git a/linux/CMakeLists.txt b/linux/CMakeLists.txt index d7e6ca93..7b99da46 100644 --- a/linux/CMakeLists.txt +++ b/linux/CMakeLists.txt @@ -3,7 +3,6 @@ add_subdirectory(utility) add_subdirectory(callbacks) add_subdirectory(boardtest) add_subdirectory(devices) -add_subdirectory(fsfwconfig) add_subdirectory(ipcore) target_sources(${OBSW_NAME} PUBLIC ObjectFactory.cpp InitMission.cpp) diff --git a/linux/InitMission.cpp b/linux/InitMission.cpp index 5bc8698c..4b7dc1f1 100644 --- a/linux/InitMission.cpp +++ b/linux/InitMission.cpp @@ -6,6 +6,7 @@ #include "OBSWConfig.h" #include "ObjectFactory.h" +#include "eive/objects.h" void scheduling::schedulingScex(TaskFactory& factory, PeriodicTaskIF*& scexDevHandler, PeriodicTaskIF*& scexReaderTask) { diff --git a/linux/ObjectFactory.cpp b/linux/ObjectFactory.cpp index 2fe31372..21f884f9 100644 --- a/linux/ObjectFactory.cpp +++ b/linux/ObjectFactory.cpp @@ -5,9 +5,9 @@ #include #include #include +#include #include #include -#include #include #include #include diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index dc5a5e3b..ea314b4b 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -333,14 +333,12 @@ void SpiTestClass::performPeriodicMax1227Test() { } void SpiTestClass::performMax1227Test() { + std::string deviceName = ""; #ifdef XIPHOS_Q7S std::string deviceName = q7s::SPI_DEFAULT_DEV; #elif defined(RASPBERRY_PI) - std::string deviceName = ""; #elif defined(EGSE) - std::string deviceName = ""; #elif defined(TE0720_1CFA) - std::string deviceName = ""; #endif int fd = 0; UnixFileGuard fileHelper(deviceName, &fd, O_RDWR, "SpiComIF::initializeInterface"); @@ -381,8 +379,9 @@ void SpiTestClass::max1227RadSensorTest(int fd) { DiffSel::NONE_0); spiTransferStruct[0].len = 1; transfer(fd, gpioIds::CS_RAD_SENSOR); - max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), 7, spiTransferStruct[0].len); - size_t tmpLen = spiTransferStruct[0].len; + size_t tmpSz = spiTransferStruct[0].len; + max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), 7, tmpSz); + size_t tmpLen = tmpSz; spiTransferStruct[0].len = 1; transfer(fd, gpioIds::CS_RAD_SENSOR); std::memcpy(sendBuffer.data(), sendBuffer.data() + 1, tmpLen - 1); @@ -403,7 +402,8 @@ void SpiTestClass::max1227RadSensorTest(int fd) { for (int idx = 0; idx < 8; idx++) { sif::info << "ADC raw " << idx << ": " << adcRaw[idx] << std::endl; } - max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data(), spiTransferStruct[0].len); + tmpSz = spiTransferStruct[0].len; + max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data(), tmpSz); spiTransferStruct[0].len = 1; transfer(fd, gpioIds::CS_RAD_SENSOR); usleep(65); @@ -467,7 +467,8 @@ void SpiTestClass::max1227SusTest(int fd, SusTestCfg &cfg) { spiTransferStruct[0].len = 1; transfer(fd, cfg.gpioId); - max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), 5, spiTransferStruct[0].len); + size_t tmpSz = spiTransferStruct[0].len; + max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), 5, tmpSz); transfer(fd, cfg.gpioId); uint16_t adcRaw[6] = {}; adcRaw[0] = (recvBuffer[1] << 8) | recvBuffer[2]; @@ -552,10 +553,11 @@ void SpiTestClass::max1227PlPcduTest(int fd) { spiTransferStruct[0].len = 1; transfer(fd, gpioIds::PLPCDU_ADC_CS); uint8_t n = 11; - max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), n, spiTransferStruct[0].len); - size_t dummy = 0; + size_t tmpSz = spiTransferStruct[0].len; + max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), n, tmpSz); max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data() + spiTransferStruct[0].len, - dummy); + tmpSz); + spiTransferStruct[0].len = tmpSz; // + 1 to account for temp conversion byte spiTransferStruct[0].len += 1; transfer(fd, gpioIds::PLPCDU_ADC_CS); @@ -585,9 +587,11 @@ void SpiTestClass::max1227PlPcduTest(int fd) { spiTransferStruct[0].len = 1; transfer(fd, gpioIds::PLPCDU_ADC_CS); uint8_t n = 11; - max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), n, spiTransferStruct[0].len); + size_t tmpLen = spiTransferStruct[0].len; + max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), n, tmpLen); max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data() + spiTransferStruct[0].len, - spiTransferStruct[0].len); + tmpLen); + spiTransferStruct[0].len = tmpLen; transfer(fd, gpioIds::PLPCDU_ADC_CS); uint16_t adcRaw[n + 1] = {}; for (uint8_t idx = 0; idx < n + 1; idx++) { diff --git a/linux/boardtest/UartTestClass.cpp b/linux/boardtest/UartTestClass.cpp index 4f476d4b..1f707c8f 100644 --- a/linux/boardtest/UartTestClass.cpp +++ b/linux/boardtest/UartTestClass.cpp @@ -3,7 +3,7 @@ #include // Error integer and strerror() function #include // Contains file controls like O_RDWR #include -#include +#include #include #include #include @@ -13,6 +13,7 @@ #include #include "OBSWConfig.h" +#include "eive/objects.h" #include "fsfw/globalfunctions/CRC.h" #include "fsfw/globalfunctions/DleEncoder.h" #include "fsfw/globalfunctions/arrayprinter.h" diff --git a/linux/boardtest/UartTestClass.h b/linux/boardtest/UartTestClass.h index 14d74322..6304724b 100644 --- a/linux/boardtest/UartTestClass.h +++ b/linux/boardtest/UartTestClass.h @@ -5,7 +5,7 @@ #include #include #include -#include +#include #include // Contains POSIX terminal control definitions #include diff --git a/linux/devices/ScexUartReader.cpp b/linux/devices/ScexUartReader.cpp index ca797e74..4606c921 100644 --- a/linux/devices/ScexUartReader.cpp +++ b/linux/devices/ScexUartReader.cpp @@ -6,7 +6,7 @@ #include #include #include -#include +#include #include // write(), read(), close() #include // Error integer and strerror() function 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/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 6901d8fe..512a4950 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -8,8 +8,10 @@ #include #include #include -#include +#include + +#include "eive/resultClassIds.h" #include "mission/devices/devicedefinitions/SpBase.h" namespace supv { diff --git a/linux/devices/ploc/PlocMPSoCHandler.cpp b/linux/devices/ploc/PlocMPSoCHandler.cpp index a192365f..28513314 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.cpp +++ b/linux/devices/ploc/PlocMPSoCHandler.cpp @@ -31,7 +31,7 @@ ReturnValue_t PlocMPSoCHandler::initialize() { if (result != returnvalue::OK) { return result; } - uartComIf = dynamic_cast(communicationInterface); + uartComIf = dynamic_cast(communicationInterface); if (uartComIf == nullptr) { sif::warning << "PlocMPSoCHandler::initialize: Invalid uart com if" << std::endl; return ObjectManagerIF::CHILD_INIT_FAILED; diff --git a/linux/devices/ploc/PlocMPSoCHandler.h b/linux/devices/ploc/PlocMPSoCHandler.h index fca65c7b..bd996006 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.h +++ b/linux/devices/ploc/PlocMPSoCHandler.h @@ -1,6 +1,8 @@ #ifndef BSP_Q7S_DEVICES_PLOC_PLOCMPSOCHANDLER_H_ #define BSP_Q7S_DEVICES_PLOC_PLOCMPSOCHANDLER_H_ +#include + #include #include "PlocMPSoCHelper.h" @@ -10,7 +12,6 @@ #include "fsfw/ipc/QueueFactory.h" #include "fsfw/tmtcservices/SourceSequenceCounter.h" #include "fsfw_hal/linux/gpio/Gpio.h" -#include "fsfw_hal/linux/uart/UartComIF.h" #include "linux/devices/devicedefinitions/MPSoCReturnValuesIF.h" #include "linux/devices/devicedefinitions/PlocMPSoCDefinitions.h" #include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" @@ -123,7 +124,7 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF { */ DeviceCommandId_t nextReplyId = mpsoc::NONE; - UartComIF* uartComIf = nullptr; + SerialComIF* uartComIf = nullptr; PlocMPSoCHelper* plocMPSoCHelper = nullptr; Gpio uartIsolatorSwitch; diff --git a/linux/devices/ploc/PlocMPSoCHelper.cpp b/linux/devices/ploc/PlocMPSoCHelper.cpp index 980b8889..fcd5178b 100644 --- a/linux/devices/ploc/PlocMPSoCHelper.cpp +++ b/linux/devices/ploc/PlocMPSoCHelper.cpp @@ -57,7 +57,7 @@ ReturnValue_t PlocMPSoCHelper::performOperation(uint8_t operationCode) { } ReturnValue_t PlocMPSoCHelper::setComIF(DeviceCommunicationIF* communicationInterface_) { - uartComIF = dynamic_cast(communicationInterface_); + uartComIF = dynamic_cast(communicationInterface_); if (uartComIF == nullptr) { sif::warning << "PlocMPSoCHelper::initialize: Invalid uart com if" << std::endl; return returnvalue::FAILED; diff --git a/linux/devices/ploc/PlocMPSoCHelper.h b/linux/devices/ploc/PlocMPSoCHelper.h index b669b51b..84a9f47f 100644 --- a/linux/devices/ploc/PlocMPSoCHelper.h +++ b/linux/devices/ploc/PlocMPSoCHelper.h @@ -1,6 +1,8 @@ #ifndef BSP_Q7S_DEVICES_PLOCMPSOCHELPER_H_ #define BSP_Q7S_DEVICES_PLOCMPSOCHELPER_H_ +#include + #include #include "fsfw/devicehandlers/CookieIF.h" @@ -9,7 +11,6 @@ #include "fsfw/returnvalues/returnvalue.h" #include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw/tmtcservices/SourceSequenceCounter.h" -#include "fsfw_hal/linux/uart/UartComIF.h" #include "linux/devices/devicedefinitions/PlocMPSoCDefinitions.h" #ifdef XIPHOS_Q7S #include "bsp_q7s/fs/SdCardManager.h" @@ -136,7 +137,7 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF { * Communication interface of MPSoC responsible for low level access. Must be set by the * MPSoC Handler. */ - UartComIF* uartComIF = nullptr; + SerialComIF* uartComIF = nullptr; // Communication cookie. Must be set by the MPSoC Handler CookieIF* comCookie = nullptr; // Sequence count, must be set by Ploc MPSoC Handler 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 b6783449..ddfd3733 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -49,7 +49,7 @@ ReturnValue_t PlocSupervisorHandler::initialize() { if (result != returnvalue::OK) { return result; } -#ifndef TE0720_1CFA +#ifdef XIPHOS_Q7S sdcMan = SdCardManager::instance(); #endif /* TE0720_1CFA */ if (supvHelper == nullptr) { @@ -1761,7 +1761,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"); diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 174ffa9e..a5b0a2ae 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -1,18 +1,21 @@ #ifndef MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_ #define MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_ +#include #include #include "OBSWConfig.h" -#include "bsp_q7s/fs/SdCardManager.h" #include "devices/powerSwitcherList.h" #include "fsfw/devicehandlers/DeviceHandlerBase.h" #include "fsfw/timemanager/Countdown.h" #include "fsfw_hal/linux/gpio/Gpio.h" #include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" -#include "fsfw_hal/linux/uart/UartComIF.h" #include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" +#ifdef XIPHOS_Q7S +#include "bsp_q7s/fs/SdCardManager.h" +#endif + using supv::ExecutionReport; /** @@ -114,7 +117,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { */ DeviceCommandId_t nextReplyId = supv::NONE; - UartComIF* uartComIf = nullptr; + SerialComIF* uartComIf = nullptr; LinuxLibgpioIF* gpioComIF = nullptr; Gpio uartIsolatorSwitch; @@ -141,9 +144,9 @@ 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"; diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 3bb6e764..26da089b 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -16,9 +16,10 @@ #include "bsp_q7s/fs/SdCardManager.h" #endif +#include + #include "fsfw/tasks/TaskFactory.h" #include "fsfw/timemanager/Countdown.h" -#include "fsfw_hal/linux/uart/helper.h" #include "mission/utility/Filenaming.h" #include "mission/utility/ProgressPrinter.h" #include "mission/utility/Timestamp.h" diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index 30d5fe1f..d10a5373 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -2,6 +2,7 @@ #define BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_ #include +#include #include #include @@ -13,7 +14,6 @@ #include "fsfw/osal/linux/BinarySemaphore.h" #include "fsfw/returnvalues/returnvalue.h" #include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw_hal/linux/uart/UartComIF.h" #include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" #ifdef XIPHOS_Q7S 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/devices/startracker/StrHelper.cpp b/linux/devices/startracker/StrHelper.cpp index 1f6472bb..dcf56b59 100644 --- a/linux/devices/startracker/StrHelper.cpp +++ b/linux/devices/startracker/StrHelper.cpp @@ -85,7 +85,7 @@ ReturnValue_t StrHelper::performOperation(uint8_t operationCode) { } ReturnValue_t StrHelper::setComIF(DeviceCommunicationIF* communicationInterface_) { - uartComIF = dynamic_cast(communicationInterface_); + uartComIF = dynamic_cast(communicationInterface_); if (uartComIF == nullptr) { sif::warning << "StrHelper::initialize: Invalid uart com if" << std::endl; return returnvalue::FAILED; diff --git a/linux/devices/startracker/StrHelper.h b/linux/devices/startracker/StrHelper.h index a9c80d77..ab0498d9 100644 --- a/linux/devices/startracker/StrHelper.h +++ b/linux/devices/startracker/StrHelper.h @@ -10,12 +10,13 @@ #include "bsp_q7s/fs/SdCardManager.h" #endif +#include + #include "fsfw/devicehandlers/CookieIF.h" #include "fsfw/objectmanager/SystemObject.h" #include "fsfw/osal/linux/BinarySemaphore.h" #include "fsfw/returnvalues/returnvalue.h" #include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw_hal/linux/uart/UartComIF.h" extern "C" { #include "thirdparty/arcsec_star_tracker/client/generated/actionreq.h" @@ -255,7 +256,7 @@ class StrHelper : public SystemObject, public ExecutableObjectIF { * UART communication object responsible for low level access of star tracker * Must be set by star tracker handler */ - UartComIF* uartComIF = nullptr; + SerialComIF* uartComIF = nullptr; // Communication cookie. Must be set by the star tracker handler CookieIF* comCookie = nullptr; 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" From 02df949a4806916fb247f8910c02ad9882459fc0 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 17:42:19 +0100 Subject: [PATCH 066/176] this seems to work --- CMakeLists.txt | 7 +++---- bsp_q7s/core/ObjectFactory.cpp | 10 +++++----- bsp_q7s/core/ObjectFactory.h | 6 +++--- bsp_q7s/fmObjectFactory.cpp | 2 +- linux/CMakeLists.txt | 4 ++++ linux/boardtest/SpiTestClass.cpp | 2 +- {bsp_linux_board => linux}/fsfwconfig/CMakeLists.txt | 0 {bsp_linux_board => linux}/fsfwconfig/FSFWConfig.h.in | 0 .../fsfwconfig/events/subsystemIdRanges.h | 0 .../fsfwconfig/events/translateEvents.cpp | 0 .../fsfwconfig/events/translateEvents.h | 0 .../fsfwconfig/ipc/MissionMessageTypes.cpp | 0 .../fsfwconfig/ipc/MissionMessageTypes.h | 0 .../fsfwconfig/objects/systemObjectList.h | 0 .../fsfwconfig/objects/translateObjects.cpp | 0 .../fsfwconfig/objects/translateObjects.h | 0 .../pollingsequence/pollingSequenceFactory.cpp | 0 .../pollingsequence/pollingSequenceFactory.h | 0 .../fsfwconfig/returnvalues/classIds.h | 0 19 files changed, 17 insertions(+), 14 deletions(-) rename {bsp_linux_board => linux}/fsfwconfig/CMakeLists.txt (100%) rename {bsp_linux_board => linux}/fsfwconfig/FSFWConfig.h.in (100%) rename {bsp_linux_board => linux}/fsfwconfig/events/subsystemIdRanges.h (100%) rename {bsp_linux_board => linux}/fsfwconfig/events/translateEvents.cpp (100%) rename {bsp_linux_board => linux}/fsfwconfig/events/translateEvents.h (100%) rename {bsp_linux_board => linux}/fsfwconfig/ipc/MissionMessageTypes.cpp (100%) rename {bsp_linux_board => linux}/fsfwconfig/ipc/MissionMessageTypes.h (100%) rename {bsp_linux_board => linux}/fsfwconfig/objects/systemObjectList.h (100%) rename {bsp_linux_board => linux}/fsfwconfig/objects/translateObjects.cpp (100%) rename {bsp_linux_board => linux}/fsfwconfig/objects/translateObjects.h (100%) rename {bsp_linux_board => linux}/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp (100%) rename {bsp_linux_board => linux}/fsfwconfig/pollingsequence/pollingSequenceFactory.h (100%) rename {bsp_linux_board => linux}/fsfwconfig/returnvalues/classIds.h (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index f940ea0f..97b7601c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -235,10 +235,6 @@ set(LIB_JSON_PATH ${THIRD_PARTY_FOLDER}/json) set(FSFW_WARNING_SHADOW_LOCAL_GCC OFF) set(EIVE_ADD_LINUX_FILES OFF) -if(UNIX) - set(EIVE_ADD_LINUX_FILES ON) -endif() - # Analyse different OS and architecture/target options, determine BSP_PATH, # display information about compiler etc. pre_source_hw_os_config() @@ -257,12 +253,15 @@ if(TGT_BSP) set(FSFW_CONFIG_PATH "linux/fsfwconfig") if(NOT BUILD_Q7S_SIMPLE_MODE) set(EIVE_ADD_LINUX_FILES TRUE) + set(EIVE_ADD_LINUX_FSFWCONFIG TRUE) set(ADD_GOMSPACE_CSP TRUE) set(ADD_GOMSPACE_CLIENTS TRUE) set(FSFW_HAL_ADD_LINUX ON) set(FSFW_HAL_LINUX_ADD_LIBGPIOD ON) set(FSFW_HAL_LINUX_ADD_PERIPHERAL_DRIVERS ON) endif() + elseif(UNIX) + set(EIVE_ADD_LINUX_FILES ON) endif() if(TGT_BSP MATCHES "arm/raspberrypi") diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index 718594e1..07eb0d22 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -71,8 +71,8 @@ #include "fsfw_hal/linux/i2c/I2cCookie.h" #include "fsfw_hal/linux/spi/SpiComIF.h" #include "fsfw_hal/linux/spi/SpiCookie.h" -#include "fsfw_hal/linux/uart/UartComIF.h" -#include "fsfw_hal/linux/uart/UartCookie.h" +#include "fsfw_hal/linux/serial/SerialComIF.h" +#include "fsfw_hal/linux/serial/SerialCookie.h" #include "mission/core/GenericFactory.h" #include "mission/devices/ACUHandler.h" #include "mission/devices/BpxBatteryHandler.h" @@ -137,7 +137,7 @@ void ObjectFactory::createTmpComponents() { (void)tmp1075Handler_2; } -void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, UartComIF** uartComIF, +void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, SerialComIF** uartComIF, SpiComIF** spiMainComIF, I2cComIF** i2cComIF, SpiComIF** spiRWComIF) { if (gpioComIF == nullptr or uartComIF == nullptr or spiMainComIF == nullptr or @@ -150,7 +150,7 @@ void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, Ua /* Communication interfaces */ new CspComIF(objects::CSP_COM_IF); *i2cComIF = new I2cComIF(objects::I2C_COM_IF); - *uartComIF = new UartComIF(objects::UART_COM_IF); + *uartComIF = new SerialComIF(objects::UART_COM_IF); *spiMainComIF = new SpiComIF(objects::SPI_MAIN_COM_IF, q7s::SPI_DEFAULT_DEV, **gpioComIF); *spiRWComIF = new SpiComIF(objects::SPI_RW_COM_IF, q7s::SPI_RW_DEV, **gpioComIF); } @@ -230,7 +230,7 @@ ReturnValue_t ObjectFactory::createRadSensorComponent(LinuxLibgpioIF* gpioComIF) return returnvalue::OK; } -void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComIF* uartComIF, +void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, SerialComIF* uartComIF, PowerSwitchIF* pwrSwitcher) { using namespace gpio; GpioCookie* gpioCookieAcsBoard = new GpioCookie(); diff --git a/bsp_q7s/core/ObjectFactory.h b/bsp_q7s/core/ObjectFactory.h index 40a4e2ed..c67353c4 100644 --- a/bsp_q7s/core/ObjectFactory.h +++ b/bsp_q7s/core/ObjectFactory.h @@ -9,7 +9,7 @@ #include class LinuxLibgpioIF; -class UartComIF; +class SerialComIF; class SpiComIF; class I2cComIF; class PowerSwitchIF; @@ -22,7 +22,7 @@ namespace ObjectFactory { void setStatics(); void produce(void* args); -void createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, UartComIF** uartComIF, +void createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, SerialComIF** uartComIF, SpiComIF** spiMainComIF, I2cComIF** i2cComIF, SpiComIF** spiRwComIF); void createPcduComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF** pwrSwitcher); @@ -30,7 +30,7 @@ void createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF, PowerSwitchIF* pwrSwitcher); void createTmpComponents(); ReturnValue_t createRadSensorComponent(LinuxLibgpioIF* gpioComIF); -void createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComIF* uartComIF, +void createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, SerialComIF* uartComIF, PowerSwitchIF* pwrSwitcher); void createHeaterComponents(GpioIF* gpioIF, PowerSwitchIF* pwrSwitcher, HealthTableIF* healthTable); void createImtqComponents(PowerSwitchIF* pwrSwitcher); diff --git a/bsp_q7s/fmObjectFactory.cpp b/bsp_q7s/fmObjectFactory.cpp index 6ac2498a..c56dcf8d 100644 --- a/bsp_q7s/fmObjectFactory.cpp +++ b/bsp_q7s/fmObjectFactory.cpp @@ -21,7 +21,7 @@ void ObjectFactory::produce(void* args) { ObjectFactory::produceGenericObjects(&healthTable, &pusFunnel, &cfdpFunnel); LinuxLibgpioIF* gpioComIF = nullptr; - UartComIF* uartComIF = nullptr; + SerialComIF* uartComIF = nullptr; SpiComIF* spiMainComIF = nullptr; I2cComIF* i2cComIF = nullptr; PowerSwitchIF* pwrSwitcher = nullptr; diff --git a/linux/CMakeLists.txt b/linux/CMakeLists.txt index 7b99da46..f8c8935f 100644 --- a/linux/CMakeLists.txt +++ b/linux/CMakeLists.txt @@ -5,4 +5,8 @@ add_subdirectory(boardtest) add_subdirectory(devices) add_subdirectory(ipcore) +if(EIVE_ADD_LINUX_FSFWCONFIG) + add_subdirectory(fsfwconfig) +endif() + target_sources(${OBSW_NAME} PUBLIC ObjectFactory.cpp InitMission.cpp) diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index ea314b4b..575bd6cb 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -335,7 +335,7 @@ void SpiTestClass::performPeriodicMax1227Test() { void SpiTestClass::performMax1227Test() { std::string deviceName = ""; #ifdef XIPHOS_Q7S - std::string deviceName = q7s::SPI_DEFAULT_DEV; + deviceName = q7s::SPI_DEFAULT_DEV; #elif defined(RASPBERRY_PI) #elif defined(EGSE) #elif defined(TE0720_1CFA) diff --git a/bsp_linux_board/fsfwconfig/CMakeLists.txt b/linux/fsfwconfig/CMakeLists.txt similarity index 100% rename from bsp_linux_board/fsfwconfig/CMakeLists.txt rename to linux/fsfwconfig/CMakeLists.txt diff --git a/bsp_linux_board/fsfwconfig/FSFWConfig.h.in b/linux/fsfwconfig/FSFWConfig.h.in similarity index 100% rename from bsp_linux_board/fsfwconfig/FSFWConfig.h.in rename to linux/fsfwconfig/FSFWConfig.h.in diff --git a/bsp_linux_board/fsfwconfig/events/subsystemIdRanges.h b/linux/fsfwconfig/events/subsystemIdRanges.h similarity index 100% rename from bsp_linux_board/fsfwconfig/events/subsystemIdRanges.h rename to linux/fsfwconfig/events/subsystemIdRanges.h diff --git a/bsp_linux_board/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp similarity index 100% rename from bsp_linux_board/fsfwconfig/events/translateEvents.cpp rename to linux/fsfwconfig/events/translateEvents.cpp diff --git a/bsp_linux_board/fsfwconfig/events/translateEvents.h b/linux/fsfwconfig/events/translateEvents.h similarity index 100% rename from bsp_linux_board/fsfwconfig/events/translateEvents.h rename to linux/fsfwconfig/events/translateEvents.h diff --git a/bsp_linux_board/fsfwconfig/ipc/MissionMessageTypes.cpp b/linux/fsfwconfig/ipc/MissionMessageTypes.cpp similarity index 100% rename from bsp_linux_board/fsfwconfig/ipc/MissionMessageTypes.cpp rename to linux/fsfwconfig/ipc/MissionMessageTypes.cpp diff --git a/bsp_linux_board/fsfwconfig/ipc/MissionMessageTypes.h b/linux/fsfwconfig/ipc/MissionMessageTypes.h similarity index 100% rename from bsp_linux_board/fsfwconfig/ipc/MissionMessageTypes.h rename to linux/fsfwconfig/ipc/MissionMessageTypes.h diff --git a/bsp_linux_board/fsfwconfig/objects/systemObjectList.h b/linux/fsfwconfig/objects/systemObjectList.h similarity index 100% rename from bsp_linux_board/fsfwconfig/objects/systemObjectList.h rename to linux/fsfwconfig/objects/systemObjectList.h diff --git a/bsp_linux_board/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp similarity index 100% rename from bsp_linux_board/fsfwconfig/objects/translateObjects.cpp rename to linux/fsfwconfig/objects/translateObjects.cpp diff --git a/bsp_linux_board/fsfwconfig/objects/translateObjects.h b/linux/fsfwconfig/objects/translateObjects.h similarity index 100% rename from bsp_linux_board/fsfwconfig/objects/translateObjects.h rename to linux/fsfwconfig/objects/translateObjects.h diff --git a/bsp_linux_board/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp similarity index 100% rename from bsp_linux_board/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp rename to linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp diff --git a/bsp_linux_board/fsfwconfig/pollingsequence/pollingSequenceFactory.h b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.h similarity index 100% rename from bsp_linux_board/fsfwconfig/pollingsequence/pollingSequenceFactory.h rename to linux/fsfwconfig/pollingsequence/pollingSequenceFactory.h diff --git a/bsp_linux_board/fsfwconfig/returnvalues/classIds.h b/linux/fsfwconfig/returnvalues/classIds.h similarity index 100% rename from bsp_linux_board/fsfwconfig/returnvalues/classIds.h rename to linux/fsfwconfig/returnvalues/classIds.h From a74ddbbb9f4b8d8680cee5ce6bac3dad84c12110 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 17:46:57 +0100 Subject: [PATCH 067/176] small bugfix --- linux/boardtest/SpiTestClass.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index 575bd6cb..91e8893c 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -555,9 +555,10 @@ void SpiTestClass::max1227PlPcduTest(int fd) { uint8_t n = 11; size_t tmpSz = spiTransferStruct[0].len; max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), n, tmpSz); - max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data() + spiTransferStruct[0].len, - tmpSz); spiTransferStruct[0].len = tmpSz; + size_t dummy = 0; + max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data() + spiTransferStruct[0].len, + dummy); // + 1 to account for temp conversion byte spiTransferStruct[0].len += 1; transfer(fd, gpioIds::PLPCDU_ADC_CS); From ceba3b9dcaa1670bf573f62d04cd89b5888772f1 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 10 Nov 2022 18:07:59 +0100 Subject: [PATCH 068/176] renaming of fsfw_hal components --- bsp_egse/ObjectFactory.cpp | 6 +- bsp_linux_board/ObjectFactory.cpp | 6 +- bsp_q7s/core/ObjectFactory.cpp | 14 +- bsp_q7s/core/ObjectFactory.h | 6 +- bsp_q7s/em/emObjectFactory.cpp | 2 +- bsp_q7s/fmObjectFactory.cpp | 2 +- bsp_te0720_1cfa/ObjectFactory.cpp | 6 +- common/config/devConf.h | 2 +- fsfw | 2 +- generators/bsp_q7s_objects.csv | 6 +- generators/bsp_q7s_returnvalues.csv | 664 +++++++++--------- generators/events/translateEvents.cpp | 2 +- generators/objects/translateObjects.cpp | 20 +- linux/ObjectFactory.cpp | 2 +- linux/boardtest/UartTestClass.cpp | 2 +- linux/boardtest/UartTestClass.h | 2 +- linux/devices/ScexUartReader.cpp | 2 +- linux/devices/ploc/PlocMPSoCHandler.cpp | 2 +- linux/devices/ploc/PlocMPSoCHandler.h | 4 +- linux/devices/ploc/PlocMPSoCHelper.cpp | 2 +- linux/devices/ploc/PlocMPSoCHelper.h | 4 +- linux/devices/ploc/PlocSupervisorHandler.cpp | 2 +- linux/devices/ploc/PlocSupervisorHandler.h | 4 +- linux/devices/ploc/PlocSupvHelper.cpp | 2 +- linux/devices/ploc/PlocSupvHelper.h | 6 +- .../devices/startracker/StarTrackerHandler.h | 2 +- linux/devices/startracker/StrHelper.cpp | 2 +- linux/devices/startracker/StrHelper.h | 4 +- linux/fsfwconfig/events/translateEvents.cpp | 2 +- linux/fsfwconfig/objects/translateObjects.cpp | 20 +- tmtc | 2 +- 31 files changed, 407 insertions(+), 397 deletions(-) diff --git a/bsp_egse/ObjectFactory.cpp b/bsp_egse/ObjectFactory.cpp index 8d5e3416..b13af722 100644 --- a/bsp_egse/ObjectFactory.cpp +++ b/bsp_egse/ObjectFactory.cpp @@ -1,8 +1,8 @@ #include "ObjectFactory.h" #include -#include -#include +#include +#include #include "OBSWConfig.h" #include "busConf.h" @@ -39,7 +39,7 @@ void ObjectFactory::produce(void* args) { UartCookie* starTrackerCookie = new UartCookie(objects::STAR_TRACKER, egse::STAR_TRACKER_UART, UartModes::NON_CANONICAL, uart::STAR_TRACKER_BAUD, startracker::MAX_FRAME_SIZE * 2 + 2); - new UartComIF(objects::UART_COM_IF); + newSerialComIF(objects::UART_COM_IF); starTrackerCookie->setNoFixedSizeReply(); StrHelper* strHelper = new StrHelper(objects::STR_HELPER); StarTrackerHandler* starTrackerHandler = new StarTrackerHandler( diff --git a/bsp_linux_board/ObjectFactory.cpp b/bsp_linux_board/ObjectFactory.cpp index 8ebcdc8c..53db052c 100644 --- a/bsp_linux_board/ObjectFactory.cpp +++ b/bsp_linux_board/ObjectFactory.cpp @@ -34,8 +34,8 @@ #include "fsfw/osal/common/UdpTmTcBridge.h" #endif -#include -#include +#include +#include #include "fsfw_hal/common/gpio/GpioCookie.h" #include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h" @@ -202,7 +202,7 @@ void ObjectFactory::createTestTasks() { #if OBSW_ADD_UART_TEST_CODE == 1 new UartTestClass(objects::UART_TEST); #else - new UartComIF(objects::UART_COM_IF); + newSerialComIF(objects::UART_COM_IF); #endif #if RPI_LOOPBACK_TEST_GPIO == 1 diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index bc46efb5..f5397e04 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -69,10 +69,10 @@ #include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" #include "fsfw_hal/linux/i2c/I2cComIF.h" #include "fsfw_hal/linux/i2c/I2cCookie.h" +#include "fsfw_hal/linux/serial/SerialComIF.h" +#include "fsfw_hal/linux/serial/SerialCookie.h" #include "fsfw_hal/linux/spi/SpiComIF.h" #include "fsfw_hal/linux/spi/SpiCookie.h" -#include "fsfw_hal/linux/uart/UartComIF.h" -#include "fsfw_hal/linux/uart/UartCookie.h" #include "mission/core/GenericFactory.h" #include "mission/devices/ACUHandler.h" #include "mission/devices/BpxBatteryHandler.h" @@ -137,9 +137,9 @@ void ObjectFactory::createTmpComponents() { (void)tmp1075Handler_2; } -void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, UartComIF** uartComIF, - SpiComIF** spiMainComIF, I2cComIF** i2cComIF, - SpiComIF** spiRWComIF) { +void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, + SerialComIF** uartComIF, SpiComIF** spiMainComIF, + I2cComIF** i2cComIF, SpiComIF** spiRWComIF) { if (gpioComIF == nullptr or uartComIF == nullptr or spiMainComIF == nullptr or spiRWComIF == nullptr) { sif::error << "ObjectFactory::createCommunicationInterfaces: Invalid passed ComIF pointer" @@ -150,7 +150,7 @@ void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, Ua /* Communication interfaces */ new CspComIF(objects::CSP_COM_IF); *i2cComIF = new I2cComIF(objects::I2C_COM_IF); - *uartComIF = new UartComIF(objects::UART_COM_IF); + *uartComIF = new SerialComIF(objects::UART_COM_IF); *spiMainComIF = new SpiComIF(objects::SPI_MAIN_COM_IF, q7s::SPI_DEFAULT_DEV, **gpioComIF); *spiRWComIF = new SpiComIF(objects::SPI_RW_COM_IF, q7s::SPI_RW_DEV, **gpioComIF); } @@ -230,7 +230,7 @@ ReturnValue_t ObjectFactory::createRadSensorComponent(LinuxLibgpioIF* gpioComIF) return returnvalue::OK; } -void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComIF* uartComIF, +void ObjectFactory::createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, SerialComIF* uartComIF, PowerSwitchIF* pwrSwitcher) { using namespace gpio; GpioCookie* gpioCookieAcsBoard = new GpioCookie(); diff --git a/bsp_q7s/core/ObjectFactory.h b/bsp_q7s/core/ObjectFactory.h index 40a4e2ed..c67353c4 100644 --- a/bsp_q7s/core/ObjectFactory.h +++ b/bsp_q7s/core/ObjectFactory.h @@ -9,7 +9,7 @@ #include class LinuxLibgpioIF; -class UartComIF; +class SerialComIF; class SpiComIF; class I2cComIF; class PowerSwitchIF; @@ -22,7 +22,7 @@ namespace ObjectFactory { void setStatics(); void produce(void* args); -void createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, UartComIF** uartComIF, +void createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, SerialComIF** uartComIF, SpiComIF** spiMainComIF, I2cComIF** i2cComIF, SpiComIF** spiRwComIF); void createPcduComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF** pwrSwitcher); @@ -30,7 +30,7 @@ void createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF, PowerSwitchIF* pwrSwitcher); void createTmpComponents(); ReturnValue_t createRadSensorComponent(LinuxLibgpioIF* gpioComIF); -void createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, UartComIF* uartComIF, +void createAcsBoardComponents(LinuxLibgpioIF* gpioComIF, SerialComIF* uartComIF, PowerSwitchIF* pwrSwitcher); void createHeaterComponents(GpioIF* gpioIF, PowerSwitchIF* pwrSwitcher, HealthTableIF* healthTable); void createImtqComponents(PowerSwitchIF* pwrSwitcher); diff --git a/bsp_q7s/em/emObjectFactory.cpp b/bsp_q7s/em/emObjectFactory.cpp index 8667154b..aba884f1 100644 --- a/bsp_q7s/em/emObjectFactory.cpp +++ b/bsp_q7s/em/emObjectFactory.cpp @@ -22,7 +22,7 @@ void ObjectFactory::produce(void* args) { ObjectFactory::produceGenericObjects(&healthTable, &pusFunnel, &cfdpFunnel); LinuxLibgpioIF* gpioComIF = nullptr; - UartComIF* uartComIF = nullptr; + SerialComIF* uartComIF = nullptr; SpiComIF* spiMainComIF = nullptr; I2cComIF* i2cComIF = nullptr; SpiComIF* spiRwComIF = nullptr; diff --git a/bsp_q7s/fmObjectFactory.cpp b/bsp_q7s/fmObjectFactory.cpp index 6ac2498a..c56dcf8d 100644 --- a/bsp_q7s/fmObjectFactory.cpp +++ b/bsp_q7s/fmObjectFactory.cpp @@ -21,7 +21,7 @@ void ObjectFactory::produce(void* args) { ObjectFactory::produceGenericObjects(&healthTable, &pusFunnel, &cfdpFunnel); LinuxLibgpioIF* gpioComIF = nullptr; - UartComIF* uartComIF = nullptr; + SerialComIF* uartComIF = nullptr; SpiComIF* spiMainComIF = nullptr; I2cComIF* i2cComIF = nullptr; PowerSwitchIF* pwrSwitcher = nullptr; diff --git a/bsp_te0720_1cfa/ObjectFactory.cpp b/bsp_te0720_1cfa/ObjectFactory.cpp index fe699e50..2877c4e0 100644 --- a/bsp_te0720_1cfa/ObjectFactory.cpp +++ b/bsp_te0720_1cfa/ObjectFactory.cpp @@ -12,8 +12,8 @@ #include "fsfw/tmtcservices/PusServiceBase.h" #include "fsfw_hal/linux/i2c/I2cComIF.h" #include "fsfw_hal/linux/i2c/I2cCookie.h" -#include "fsfw_hal/linux/uart/UartComIF.h" -#include "fsfw_hal/linux/uart/UartCookie.h" +#include "fsfw_hal/linux/serial/SerialComIF.h" +#include "fsfw_hal/linux/serial/SerialCookie.h" #include "fsfw_hal/common/gpio/GpioCookie.h" #include "linux/ObjectFactory.h" #include "linux/devices/ploc/PlocMPSoCHandler.h" @@ -59,7 +59,7 @@ void ObjectFactory::produce(void* args) { ObjectFactory::produceGenericObjects(); LinuxLibgpioIF* gpioComIF = new LinuxLibgpioIF(objects::GPIO_IF);; - new UartComIF(objects::UART_COM_IF); + newSerialComIF(objects::UART_COM_IF); #if OBSW_ADD_PLOC_MPSOC == 1 UartCookie* mpsocUartCookie = new UartCookie(objects::PLOC_MPSOC_HANDLER, te0720_1cfa::MPSOC_UART, diff --git a/common/config/devConf.h b/common/config/devConf.h index 88e78e1e..e5188324 100644 --- a/common/config/devConf.h +++ b/common/config/devConf.h @@ -4,8 +4,8 @@ #include #include "fsfw/timemanager/clockDefinitions.h" +#include "fsfw_hal/linux/serial/SerialCookie.h" #include "fsfw_hal/linux/spi/spiDefinitions.h" -#include "fsfw_hal/linux/uart/UartCookie.h" /** * SPI configuration will be contained here to let the device handlers remain independent diff --git a/fsfw b/fsfw index 177c39dd..39946bff 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 177c39dd53198a1b05e2f40fc3c5e88e7f7c2e0b +Subproject commit 39946bff58db7c5ac9016ca3156abb059560d9cb diff --git a/generators/bsp_q7s_objects.csv b/generators/bsp_q7s_objects.csv index 20cd0923..10ac10ed 100644 --- a/generators/bsp_q7s_objects.csv +++ b/generators/bsp_q7s_objects.csv @@ -131,12 +131,14 @@ 0x73000002;SUS_BOARD_ASS 0x73000003;TCS_BOARD_ASS 0x73000004;RW_ASS -0x73000005;CFDP_HANDLER -0x73000006;CFDP_DISTRIBUTOR +0x73000006;CAM_SWITCHER 0x73000100;TM_FUNNEL 0x73000101;PUS_TM_FUNNEL 0x73000102;CFDP_TM_FUNNEL +0x73000205;CFDP_HANDLER +0x73000206;CFDP_DISTRIBUTOR 0x73010000;EIVE_SYSTEM 0x73010001;ACS_SUBSYSTEM +0x73010002;PL_SUBSYSTEM 0x73500000;CCSDS_IP_CORE_BRIDGE 0xFFFFFFFF;NO_OBJECT diff --git a/generators/bsp_q7s_returnvalues.csv b/generators/bsp_q7s_returnvalues.csv index 72c0868f..72c805b5 100644 --- a/generators/bsp_q7s_returnvalues.csv +++ b/generators/bsp_q7s_returnvalues.csv @@ -1,13 +1,22 @@ 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 -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 +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 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 @@ -20,21 +29,12 @@ 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 -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 +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 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,130 +44,111 @@ 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 -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 +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 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 -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 +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 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 @@ -208,95 +189,9 @@ 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 -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 +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 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 @@ -305,39 +200,20 @@ 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 -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 -0x1101;AL_Full;;1;ARRAY_LIST;fsfw/src/fsfw/container/ArrayList.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 -0x1501;FM_KeyAlreadyExists;;1;FIXED_MAP;fsfw/src/fsfw/container/FixedMap.h -0x1502;FM_MapFull;;2;FIXED_MAP;fsfw/src/fsfw/container/FixedMap.h -0x1503;FM_KeyDoesNotExist;;3;FIXED_MAP;fsfw/src/fsfw/container/FixedMap.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 +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 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 @@ -345,23 +221,76 @@ 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 -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 +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 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 @@ -380,34 +309,72 @@ 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 -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 +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 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 @@ -417,12 +384,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 -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 +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 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 @@ -444,28 +411,58 @@ 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 -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/uart/UartComIF.h -0x4602;HURT_UartReadSizeMissmatch;;2;HAL_UART;fsfw/src/fsfw_hal/linux/uart/UartComIF.h -0x4603;HURT_UartRxBufferTooSmall;;3;HAL_UART;fsfw/src/fsfw_hal/linux/uart/UartComIF.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 +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 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 @@ -478,4 +475,3 @@ 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 dfaec6e0..87c790d7 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** * @brief Auto-generated event translation file. Contains 234 translations. * @details - * Generated on: 2022-11-03 16:11:14 + * Generated on: 2022-11-10 18:07:26 */ #include "translateEvents.h" diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index 1e676cbc..cfb7f9a5 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -1,8 +1,8 @@ /** * @brief Auto-generated object translation file. * @details - * Contains 142 translations. - * Generated on: 2022-11-03 16:11:14 + * Contains 144 translations. + * Generated on: 2022-11-10 18:07:26 */ #include "translateObjects.h" @@ -139,13 +139,15 @@ 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 *CFDP_HANDLER_STRING = "CFDP_HANDLER"; -const char *CFDP_DISTRIBUTOR_STRING = "CFDP_DISTRIBUTOR"; +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"; @@ -417,20 +419,24 @@ const char *translateObject(object_id_t object) { return TCS_BOARD_ASS_STRING; case 0x73000004: return RW_ASS_STRING; - case 0x73000005: - return CFDP_HANDLER_STRING; case 0x73000006: - return CFDP_DISTRIBUTOR_STRING; + 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: diff --git a/linux/ObjectFactory.cpp b/linux/ObjectFactory.cpp index 2fe31372..21f884f9 100644 --- a/linux/ObjectFactory.cpp +++ b/linux/ObjectFactory.cpp @@ -5,9 +5,9 @@ #include #include #include +#include #include #include -#include #include #include #include diff --git a/linux/boardtest/UartTestClass.cpp b/linux/boardtest/UartTestClass.cpp index 4f476d4b..2c914d74 100644 --- a/linux/boardtest/UartTestClass.cpp +++ b/linux/boardtest/UartTestClass.cpp @@ -3,7 +3,7 @@ #include // Error integer and strerror() function #include // Contains file controls like O_RDWR #include -#include +#include #include #include #include diff --git a/linux/boardtest/UartTestClass.h b/linux/boardtest/UartTestClass.h index 14d74322..6304724b 100644 --- a/linux/boardtest/UartTestClass.h +++ b/linux/boardtest/UartTestClass.h @@ -5,7 +5,7 @@ #include #include #include -#include +#include #include // Contains POSIX terminal control definitions #include diff --git a/linux/devices/ScexUartReader.cpp b/linux/devices/ScexUartReader.cpp index 38a4025f..ce59472d 100644 --- a/linux/devices/ScexUartReader.cpp +++ b/linux/devices/ScexUartReader.cpp @@ -6,7 +6,7 @@ #include #include #include -#include +#include #include // write(), read(), close() #include // Error integer and strerror() function diff --git a/linux/devices/ploc/PlocMPSoCHandler.cpp b/linux/devices/ploc/PlocMPSoCHandler.cpp index a192365f..28513314 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.cpp +++ b/linux/devices/ploc/PlocMPSoCHandler.cpp @@ -31,7 +31,7 @@ ReturnValue_t PlocMPSoCHandler::initialize() { if (result != returnvalue::OK) { return result; } - uartComIf = dynamic_cast(communicationInterface); + uartComIf = dynamic_cast(communicationInterface); if (uartComIf == nullptr) { sif::warning << "PlocMPSoCHandler::initialize: Invalid uart com if" << std::endl; return ObjectManagerIF::CHILD_INIT_FAILED; diff --git a/linux/devices/ploc/PlocMPSoCHandler.h b/linux/devices/ploc/PlocMPSoCHandler.h index fca65c7b..a7d7a427 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.h +++ b/linux/devices/ploc/PlocMPSoCHandler.h @@ -10,7 +10,7 @@ #include "fsfw/ipc/QueueFactory.h" #include "fsfw/tmtcservices/SourceSequenceCounter.h" #include "fsfw_hal/linux/gpio/Gpio.h" -#include "fsfw_hal/linux/uart/UartComIF.h" +#include "fsfw_hal/linux/serial/SerialComIF.h" #include "linux/devices/devicedefinitions/MPSoCReturnValuesIF.h" #include "linux/devices/devicedefinitions/PlocMPSoCDefinitions.h" #include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" @@ -123,7 +123,7 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF { */ DeviceCommandId_t nextReplyId = mpsoc::NONE; - UartComIF* uartComIf = nullptr; + SerialComIF* uartComIf = nullptr; PlocMPSoCHelper* plocMPSoCHelper = nullptr; Gpio uartIsolatorSwitch; diff --git a/linux/devices/ploc/PlocMPSoCHelper.cpp b/linux/devices/ploc/PlocMPSoCHelper.cpp index 980b8889..fcd5178b 100644 --- a/linux/devices/ploc/PlocMPSoCHelper.cpp +++ b/linux/devices/ploc/PlocMPSoCHelper.cpp @@ -57,7 +57,7 @@ ReturnValue_t PlocMPSoCHelper::performOperation(uint8_t operationCode) { } ReturnValue_t PlocMPSoCHelper::setComIF(DeviceCommunicationIF* communicationInterface_) { - uartComIF = dynamic_cast(communicationInterface_); + uartComIF = dynamic_cast(communicationInterface_); if (uartComIF == nullptr) { sif::warning << "PlocMPSoCHelper::initialize: Invalid uart com if" << std::endl; return returnvalue::FAILED; diff --git a/linux/devices/ploc/PlocMPSoCHelper.h b/linux/devices/ploc/PlocMPSoCHelper.h index b669b51b..c39cc758 100644 --- a/linux/devices/ploc/PlocMPSoCHelper.h +++ b/linux/devices/ploc/PlocMPSoCHelper.h @@ -9,7 +9,7 @@ #include "fsfw/returnvalues/returnvalue.h" #include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw/tmtcservices/SourceSequenceCounter.h" -#include "fsfw_hal/linux/uart/UartComIF.h" +#include "fsfw_hal/linux/serial/SerialComIF.h" #include "linux/devices/devicedefinitions/PlocMPSoCDefinitions.h" #ifdef XIPHOS_Q7S #include "bsp_q7s/fs/SdCardManager.h" @@ -136,7 +136,7 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF { * Communication interface of MPSoC responsible for low level access. Must be set by the * MPSoC Handler. */ - UartComIF* uartComIF = nullptr; + SerialComIF* uartComIF = nullptr; // Communication cookie. Must be set by the MPSoC Handler CookieIF* comCookie = nullptr; // Sequence count, must be set by Ploc MPSoC Handler diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index dcdff2c3..6bc224e6 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -46,7 +46,7 @@ ReturnValue_t PlocSupervisorHandler::initialize() { if (result != returnvalue::OK) { return result; } - uartComIf = dynamic_cast(communicationInterface); + uartComIf = dynamic_cast(communicationInterface); if (uartComIf == nullptr) { sif::warning << "PlocSupervisorHandler::initialize: Invalid uart com if" << std::endl; return ObjectManagerIF::CHILD_INIT_FAILED; diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 4bdf2efa..65c23fa6 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -9,7 +9,7 @@ #include "fsfw/timemanager/Countdown.h" #include "fsfw_hal/linux/gpio/Gpio.h" #include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h" -#include "fsfw_hal/linux/uart/UartComIF.h" +#include "fsfw_hal/linux/serial/SerialComIF.h" #include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" #include "linux/devices/devicedefinitions/SupvReturnValuesIF.h" @@ -110,7 +110,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { */ DeviceCommandId_t nextReplyId = supv::NONE; - UartComIF* uartComIf = nullptr; + SerialComIF* uartComIf = nullptr; LinuxLibgpioIF* gpioComIF = nullptr; Gpio uartIsolatorSwitch; diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 186eef6b..5f34cb21 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -95,7 +95,7 @@ ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { } } -ReturnValue_t PlocSupvHelper::setComIF(UartComIF* uartComIF_) { +ReturnValue_t PlocSupvHelper::setComIF(SerialComIF* uartComIF_) { if (uartComIF_ == nullptr) { sif::warning << "PlocSupvHelper::initialize: Provided invalid uart com if" << std::endl; return returnvalue::FAILED; diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 30152e65..43fda22f 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -9,7 +9,7 @@ #include "fsfw/osal/linux/BinarySemaphore.h" #include "fsfw/returnvalues/returnvalue.h" #include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw_hal/linux/uart/UartComIF.h" +#include "fsfw_hal/linux/serial/SerialComIF.h" #include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" #ifdef XIPHOS_Q7S @@ -104,7 +104,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { ReturnValue_t initialize() override; ReturnValue_t performOperation(uint8_t operationCode = 0) override; - ReturnValue_t setComIF(UartComIF* uartComfIF_); + ReturnValue_t setComIF(SerialComIF* uartComfIF_); void setComCookie(CookieIF* comCookie_); /** @@ -209,7 +209,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF { /** * Communication interface responsible for data transactions between OBC and Supervisor. */ - UartComIF* uartComIF = nullptr; + SerialComIF* uartComIF = nullptr; // Communication cookie. Must be set by the supervisor Handler CookieIF* comCookie = nullptr; diff --git a/linux/devices/startracker/StarTrackerHandler.h b/linux/devices/startracker/StarTrackerHandler.h index beab9d54..029b2bde 100644 --- a/linux/devices/startracker/StarTrackerHandler.h +++ b/linux/devices/startracker/StarTrackerHandler.h @@ -72,7 +72,7 @@ class StarTrackerHandler : public DeviceHandlerBase { ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, LocalDataPoolManager& poolManager) override; /** - * @brief Overwritten here to always read all available data from the UartComIF. + * @brief Overwritten here to always read all available data from theSerialComIF. */ virtual size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override; virtual ReturnValue_t doSendReadHook() override; diff --git a/linux/devices/startracker/StrHelper.cpp b/linux/devices/startracker/StrHelper.cpp index 1f6472bb..dcf56b59 100644 --- a/linux/devices/startracker/StrHelper.cpp +++ b/linux/devices/startracker/StrHelper.cpp @@ -85,7 +85,7 @@ ReturnValue_t StrHelper::performOperation(uint8_t operationCode) { } ReturnValue_t StrHelper::setComIF(DeviceCommunicationIF* communicationInterface_) { - uartComIF = dynamic_cast(communicationInterface_); + uartComIF = dynamic_cast(communicationInterface_); if (uartComIF == nullptr) { sif::warning << "StrHelper::initialize: Invalid uart com if" << std::endl; return returnvalue::FAILED; diff --git a/linux/devices/startracker/StrHelper.h b/linux/devices/startracker/StrHelper.h index a9c80d77..3d78f9a4 100644 --- a/linux/devices/startracker/StrHelper.h +++ b/linux/devices/startracker/StrHelper.h @@ -15,7 +15,7 @@ #include "fsfw/osal/linux/BinarySemaphore.h" #include "fsfw/returnvalues/returnvalue.h" #include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw_hal/linux/uart/UartComIF.h" +#include "fsfw_hal/linux/serial/SerialComIF.h" extern "C" { #include "thirdparty/arcsec_star_tracker/client/generated/actionreq.h" @@ -255,7 +255,7 @@ class StrHelper : public SystemObject, public ExecutableObjectIF { * UART communication object responsible for low level access of star tracker * Must be set by star tracker handler */ - UartComIF* uartComIF = nullptr; + SerialComIF* uartComIF = nullptr; // Communication cookie. Must be set by the star tracker handler CookieIF* comCookie = nullptr; diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index dfaec6e0..87c790d7 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. * @details - * Generated on: 2022-11-03 16:11:14 + * Generated on: 2022-11-10 18:07:26 */ #include "translateEvents.h" diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index 1e676cbc..cfb7f9a5 100644 --- a/linux/fsfwconfig/objects/translateObjects.cpp +++ b/linux/fsfwconfig/objects/translateObjects.cpp @@ -1,8 +1,8 @@ /** * @brief Auto-generated object translation file. * @details - * Contains 142 translations. - * Generated on: 2022-11-03 16:11:14 + * Contains 144 translations. + * Generated on: 2022-11-10 18:07:26 */ #include "translateObjects.h" @@ -139,13 +139,15 @@ 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 *CFDP_HANDLER_STRING = "CFDP_HANDLER"; -const char *CFDP_DISTRIBUTOR_STRING = "CFDP_DISTRIBUTOR"; +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"; @@ -417,20 +419,24 @@ const char *translateObject(object_id_t object) { return TCS_BOARD_ASS_STRING; case 0x73000004: return RW_ASS_STRING; - case 0x73000005: - return CFDP_HANDLER_STRING; case 0x73000006: - return CFDP_DISTRIBUTOR_STRING; + 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: diff --git a/tmtc b/tmtc index b6490a05..89285ad5 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit b6490a05ec3ed8fca30719bc657ed9e13d5a32ad +Subproject commit 89285ad511ef11582b67b307c3840a09efd0577a From 4c5515c05c04d0fd88493b1ab9a9a2c5f5b57fdc Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 11 Nov 2022 11:06:08 +0100 Subject: [PATCH 069/176] update status code handling --- .../PlocSupervisorDefinitions.h | 614 +++++++++--------- linux/devices/ploc/PlocSupervisorHandler.cpp | 42 +- 2 files changed, 318 insertions(+), 338 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 512a4950..c74e81ff 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -235,6 +235,81 @@ 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 const uint16_t APID_MASK = 0x3FF; static const uint16_t SEQUENCE_COUNT_MASK = 0xFFF; @@ -1265,6 +1340,236 @@ class VerificationReport { 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 = true; + 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 = true; + 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 = true; + 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; + } + } + protected: TmBase& readerBase; uint8_t refApid = 0; @@ -1287,59 +1592,11 @@ class AcknowledgmentReport : public VerificationReport { } 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 { @@ -1355,264 +1612,13 @@ class ExecutionReport : public VerificationReport { } return VerificationReport::parse(); } + 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; - } + VerificationReport::printStatusInformation(STATUS_PRINTOUT_PREFIX); } private: - static constexpr char STATUS_PRINTOUT_PREFIX[] = "Supervisor execution failure report 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 - }; + static constexpr char STATUS_PRINTOUT_PREFIX[] = "SUPV EXE NAK Status: "; }; class UpdateStatusReport { diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index ddfd3733..f5f333fa 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -314,6 +314,10 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d prepareSetAdcThresholdCmd(commandData); result = returnvalue::OK; break; + } + case WIPE_MRAM: { + result = prepareWipeMramCmd(commandData); + break; } // case ENABLE_NVMS: { // result = prepareEnableNvmsCommand(commandData); @@ -324,33 +328,6 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d // 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; - }*/ // Removed command // case START_MPSOC_QUIET: { // prepareEmptyCmd(APID_START_MPSOC_QUIET); @@ -417,10 +394,6 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d // result = returnvalue::OK; // break; // } - case WIPE_MRAM: { - result = prepareWipeMramCmd(commandData); - break; - } // case FIRST_MRAM_DUMP: // case CONSECUTIVE_MRAM_DUMP: // result = prepareDumpMramCmd(commandData); @@ -443,6 +416,7 @@ void PlocSupervisorHandler::fillCommandAndReplyMap() { 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); @@ -456,6 +430,9 @@ void PlocSupervisorHandler::fillCommandAndReplyMap() { insertInCommandMap(FACTORY_RESET); 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 @@ -567,9 +544,6 @@ ReturnValue_t PlocSupervisorHandler::enableReplyInReplyMap(DeviceCommandMap::ite 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 DISABLE_PERIOIC_HK_TRANSMISSION: // case START_MPSOC_QUIET: case SET_SHUTDOWN_TIMEOUT: From 7ce24ef392eb550248f7b5af08987eeb79425b0d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 11 Nov 2022 11:12:43 +0100 Subject: [PATCH 070/176] update TMP1075 dev handlers --- bsp_q7s/core/ObjectFactory.cpp | 8 ++++---- mission/devices/Tmp1075Handler.cpp | 4 ++++ mission/devices/Tmp1075Handler.h | 1 + 3 files changed, 9 insertions(+), 4 deletions(-) diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index f5397e04..326b4edc 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -129,12 +129,12 @@ void ObjectFactory::createTmpComponents() { new I2cCookie(addresses::TMP1075_TCS_2, TMP1075::MAX_REPLY_LENGTH, q7s::I2C_DEFAULT_DEV); /* Temperature sensors */ - Tmp1075Handler* tmp1075Handler_1 = + Tmp1075Handler* tmp1075Handler1 = new Tmp1075Handler(objects::TMP1075_HANDLER_1, objects::I2C_COM_IF, i2cCookieTmp1075tcs1); - (void)tmp1075Handler_1; - Tmp1075Handler* tmp1075Handler_2 = + tmp1075Handler1->setModeNormal(); + Tmp1075Handler* tmp1075Handler2 = new Tmp1075Handler(objects::TMP1075_HANDLER_2, objects::I2C_COM_IF, i2cCookieTmp1075tcs2); - (void)tmp1075Handler_2; + tmp1075Handler2->setModeNormal(); } void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, diff --git a/mission/devices/Tmp1075Handler.cpp b/mission/devices/Tmp1075Handler.cpp index 22d72999..4b7cff57 100644 --- a/mission/devices/Tmp1075Handler.cpp +++ b/mission/devices/Tmp1075Handler.cpp @@ -127,3 +127,7 @@ ReturnValue_t Tmp1075Handler::initializeLocalDataPool(localpool::DataPool &local subdp::RegularHkPeriodicParams(dataset.getSid(), false, 30.0)); return returnvalue::OK; } + +void Tmp1075Handler::setModeNormal() { + setMode(_MODE_TO_NORMAL); +} diff --git a/mission/devices/Tmp1075Handler.h b/mission/devices/Tmp1075Handler.h index 3077cf1a..7d0c0fbf 100644 --- a/mission/devices/Tmp1075Handler.h +++ b/mission/devices/Tmp1075Handler.h @@ -20,6 +20,7 @@ class Tmp1075Handler : public DeviceHandlerBase { Tmp1075Handler(object_id_t objectId, object_id_t comIF, CookieIF *comCookie); virtual ~Tmp1075Handler(); + void setModeNormal(); protected: void doStartUp() override; void doShutDown() override; From a21e938f36529a5e1b158283dced4476d4111029 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 11 Nov 2022 11:41:40 +0100 Subject: [PATCH 071/176] renamed cookie as well --- bsp_q7s/core/ObjectFactory.cpp | 12 ++++++------ fsfw | 2 +- linux/ObjectFactory.cpp | 2 +- linux/boardtest/UartTestClass.cpp | 2 +- linux/boardtest/UartTestClass.h | 2 +- linux/devices/ScexUartReader.cpp | 2 +- 6 files changed, 11 insertions(+), 11 deletions(-) diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index f5397e04..6dc08ca1 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -572,8 +572,8 @@ void ObjectFactory::createSolarArrayDeploymentComponents(PowerSwitchIF& pwrSwitc } void ObjectFactory::createSyrlinksComponents(PowerSwitchIF* pwrSwitcher) { - UartCookie* syrlinksUartCookie = - new UartCookie(objects::SYRLINKS_HK_HANDLER, q7s::UART_SYRLINKS_DEV, uart::SYRLINKS_BAUD, + auto* syrlinksUartCookie = + new SerialCookie(objects::SYRLINKS_HK_HANDLER, q7s::UART_SYRLINKS_DEV, uart::SYRLINKS_BAUD, syrlinks::MAX_REPLY_SIZE, UartModes::NON_CANONICAL); syrlinksUartCookie->setParityEven(); @@ -602,7 +602,7 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwit mpsocGpioCookie->addGpio(gpioIds::ENABLE_MPSOC_UART, gpioConfigMPSoC); gpioChecker(gpioComIF->addGpios(mpsocGpioCookie), "PLOC MPSoC"); auto mpsocCookie = - new UartCookie(objects::PLOC_MPSOC_HANDLER, q7s::UART_PLOC_MPSOC_DEV, uart::PLOC_MPSOC_BAUD, + new SerialCookie(objects::PLOC_MPSOC_HANDLER, q7s::UART_PLOC_MPSOC_DEV, uart::PLOC_MPSOC_BAUD, mpsoc::MAX_REPLY_SIZE, UartModes::NON_CANONICAL); mpsocCookie->setNoFixedSizeReply(); auto plocMpsocHelper = new PlocMPSoCHelper(objects::PLOC_MPSOC_HELPER); @@ -619,7 +619,7 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwit supvGpioCookie->addGpio(gpioIds::ENABLE_SUPV_UART, gpioConfigSupv); gpioComIF->addGpios(supvGpioCookie); auto supervisorCookie = - new UartCookie(objects::PLOC_SUPERVISOR_HANDLER, q7s::UART_PLOC_SUPERVSIOR_DEV, + 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); @@ -905,8 +905,8 @@ void ObjectFactory::createTestComponents(LinuxLibgpioIF* gpioComIF) { } void ObjectFactory::createStrComponents(PowerSwitchIF* pwrSwitcher) { - UartCookie* starTrackerCookie = - new UartCookie(objects::STAR_TRACKER, q7s::UART_STAR_TRACKER_DEV, uart::STAR_TRACKER_BAUD, + auto* starTrackerCookie = + new SerialCookie(objects::STAR_TRACKER, q7s::UART_STAR_TRACKER_DEV, uart::STAR_TRACKER_BAUD, startracker::MAX_FRAME_SIZE * 2 + 2, UartModes::NON_CANONICAL); starTrackerCookie->setNoFixedSizeReply(); StrHelper* strHelper = new StrHelper(objects::STR_HELPER); diff --git a/fsfw b/fsfw index 39946bff..e03e7f52 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 39946bff58db7c5ac9016ca3156abb059560d9cb +Subproject commit e03e7f5260eb92d1903188c5ea14ea01616600ae diff --git a/linux/ObjectFactory.cpp b/linux/ObjectFactory.cpp index 21f884f9..e35d7e96 100644 --- a/linux/ObjectFactory.cpp +++ b/linux/ObjectFactory.cpp @@ -326,7 +326,7 @@ void ObjectFactory::createRtdComponents(std::string spiDev, GpioIF* gpioComIF, void ObjectFactory::createScexComponents(std::string uartDev, PowerSwitchIF* pwrSwitcher, SdCardMountedIF& mountedIF, bool onImmediately, std::optional switchId) { - auto* cookie = new UartCookie(objects::SCEX, uartDev, uart::SCEX_BAUD, 4096); + auto* cookie = new SerialCookie(objects::SCEX, uartDev, uart::SCEX_BAUD, 4096); cookie->setTwoStopBits(); // cookie->setParityEven(); auto scexUartReader = new ScexUartReader(objects::SCEX_UART_READER); diff --git a/linux/boardtest/UartTestClass.cpp b/linux/boardtest/UartTestClass.cpp index 2c914d74..51ea237f 100644 --- a/linux/boardtest/UartTestClass.cpp +++ b/linux/boardtest/UartTestClass.cpp @@ -164,7 +164,7 @@ void UartTestClass::scexInit() { #else std::string devname = "/dev/ul-scex"; #endif - uartCookie = new UartCookie(this->getObjectId(), devname, UartBaudRate::RATE_57600, 4096); + uartCookie = new SerialCookie(this->getObjectId(), devname, UartBaudRate::RATE_57600, 4096); reader->setDebugMode(false); ReturnValue_t result = reader->initializeInterface(uartCookie); if (result != OK) { diff --git a/linux/boardtest/UartTestClass.h b/linux/boardtest/UartTestClass.h index 6304724b..05776bc0 100644 --- a/linux/boardtest/UartTestClass.h +++ b/linux/boardtest/UartTestClass.h @@ -57,7 +57,7 @@ class UartTestClass : public TestTask { scex::Cmds currCmd = scex::Cmds::PING; TestModes mode = TestModes::GPS; DleEncoder dleEncoder = DleEncoder(); - UartCookie* uartCookie = nullptr; + SerialCookie* uartCookie = nullptr; size_t encodedLen = 0; lwgps_t gpsData = {}; struct termios tty = {}; diff --git a/linux/devices/ScexUartReader.cpp b/linux/devices/ScexUartReader.cpp index ce59472d..6f615014 100644 --- a/linux/devices/ScexUartReader.cpp +++ b/linux/devices/ScexUartReader.cpp @@ -84,7 +84,7 @@ ReturnValue_t ScexUartReader::performOperation(uint8_t operationCode) { } ReturnValue_t ScexUartReader::initializeInterface(CookieIF *cookie) { - UartCookie *uartCookie = dynamic_cast(cookie); + SerialCookie *uartCookie = dynamic_cast(cookie); if (uartCookie == nullptr) { return FAILED; } From 081538004426d5e5f5aed88f5dcfecf18397eb81 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 11 Nov 2022 16:24:44 +0100 Subject: [PATCH 072/176] create all available TMP devices --- bsp_q7s/core/ObjectFactory.cpp | 38 +++--- common/config/eive/objects.h | 8 +- dummies/TemperatureSensorsDummy.cpp | 4 +- linux/fsfwconfig/devices/addresses.h | 8 +- .../pollingSequenceFactory.cpp | 114 +++++++++++------- mission/controller/ThermalController.cpp | 4 +- mission/devices/Tmp1075Handler.cpp | 4 +- mission/devices/Tmp1075Handler.h | 1 + 8 files changed, 112 insertions(+), 69 deletions(-) diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index 5245caa7..f05dfc46 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -123,18 +123,26 @@ void Factory::setStaticFrameworkObjectIds() { void ObjectFactory::setStatics() { Factory::setStaticFrameworkObjectIds(); } void ObjectFactory::createTmpComponents() { - I2cCookie* i2cCookieTmp1075tcs1 = - new I2cCookie(addresses::TMP1075_TCS_1, TMP1075::MAX_REPLY_LENGTH, q7s::I2C_DEFAULT_DEV); - I2cCookie* i2cCookieTmp1075tcs2 = - new I2cCookie(addresses::TMP1075_TCS_2, TMP1075::MAX_REPLY_LENGTH, q7s::I2C_DEFAULT_DEV); + std::array, 6> tmpDevIds = {{ + {objects::TMP1075_HANDLER_TCS_0, addresses::TMP1075_TCS_0}, + {objects::TMP1075_HANDLER_TCS_1, addresses::TMP1075_TCS_1}, + {objects::TMP1075_HANDLER_PLPCDU_0, addresses::TMP1075_PLPCDU_0}, + {objects::TMP1075_HANDLER_PLPCDU_1, addresses::TMP1075_PLPCDU_1}, + {objects::TMP1075_HANDLER_IF_BOARD, addresses::TMP1075_IF_BOARD}, + {objects::TMP1075_HANDLER_OBC_IF_BOARD, addresses::TMP1075_OBC_IF_BOARD}, + }}; + std::vector tmpDevCookies; - /* Temperature sensors */ - Tmp1075Handler* tmp1075Handler1 = - new Tmp1075Handler(objects::TMP1075_HANDLER_1, objects::I2C_COM_IF, i2cCookieTmp1075tcs1); - tmp1075Handler1->setModeNormal(); - Tmp1075Handler* tmp1075Handler2 = - new Tmp1075Handler(objects::TMP1075_HANDLER_2, objects::I2C_COM_IF, i2cCookieTmp1075tcs2); - tmp1075Handler2->setModeNormal(); + for (size_t idx = 0; idx < tmpDevIds.size(); idx++) { + tmpDevCookies.push_back( + new I2cCookie(tmpDevIds[idx].second, TMP1075::MAX_REPLY_LENGTH, q7s::I2C_DEFAULT_DEV)); + auto* tmpDevHandler = + new Tmp1075Handler(tmpDevIds[idx].first, objects::I2C_COM_IF, tmpDevCookies[idx]); + // TODO: Remove this after TCS subsystem was added + // These devices are connected to the 3V3 stack and should be powered permanently. Therefore, + // we set them to normal mode immediately here. + tmpDevHandler->setModeNormal(); + } } void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, @@ -574,7 +582,7 @@ void ObjectFactory::createSolarArrayDeploymentComponents(PowerSwitchIF& pwrSwitc void ObjectFactory::createSyrlinksComponents(PowerSwitchIF* pwrSwitcher) { auto* syrlinksUartCookie = new SerialCookie(objects::SYRLINKS_HK_HANDLER, q7s::UART_SYRLINKS_DEV, uart::SYRLINKS_BAUD, - syrlinks::MAX_REPLY_SIZE, UartModes::NON_CANONICAL); + syrlinks::MAX_REPLY_SIZE, UartModes::NON_CANONICAL); syrlinksUartCookie->setParityEven(); auto syrlinksFdir = new SyrlinksFdir(objects::SYRLINKS_HK_HANDLER); @@ -603,7 +611,7 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwit gpioChecker(gpioComIF->addGpios(mpsocGpioCookie), "PLOC MPSoC"); auto mpsocCookie = new SerialCookie(objects::PLOC_MPSOC_HANDLER, q7s::UART_PLOC_MPSOC_DEV, uart::PLOC_MPSOC_BAUD, - mpsoc::MAX_REPLY_SIZE, UartModes::NON_CANONICAL); + mpsoc::MAX_REPLY_SIZE, UartModes::NON_CANONICAL); mpsocCookie->setNoFixedSizeReply(); auto plocMpsocHelper = new PlocMPSoCHelper(objects::PLOC_MPSOC_HELPER); auto* mpsocHandler = new PlocMPSoCHandler( @@ -620,7 +628,7 @@ void ObjectFactory::createPayloadComponents(LinuxLibgpioIF* gpioComIF, PowerSwit gpioComIF->addGpios(supvGpioCookie); auto supervisorCookie = new SerialCookie(objects::PLOC_SUPERVISOR_HANDLER, q7s::UART_PLOC_SUPERVSIOR_DEV, - uart::PLOC_SUPV_BAUD, supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL); + 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( @@ -907,7 +915,7 @@ void ObjectFactory::createTestComponents(LinuxLibgpioIF* gpioComIF) { void ObjectFactory::createStrComponents(PowerSwitchIF* pwrSwitcher) { auto* starTrackerCookie = new SerialCookie(objects::STAR_TRACKER, q7s::UART_STAR_TRACKER_DEV, uart::STAR_TRACKER_BAUD, - startracker::MAX_FRAME_SIZE * 2 + 2, UartModes::NON_CANONICAL); + startracker::MAX_FRAME_SIZE * 2 + 2, UartModes::NON_CANONICAL); starTrackerCookie->setNoFixedSizeReply(); StrHelper* strHelper = new StrHelper(objects::STR_HELPER); auto starTracker = diff --git a/common/config/eive/objects.h b/common/config/eive/objects.h index 5b9ec8a0..f44c6354 100644 --- a/common/config/eive/objects.h +++ b/common/config/eive/objects.h @@ -39,8 +39,12 @@ enum commonObjects : uint32_t { GPS_CONTROLLER = 0x44130045, IMTQ_HANDLER = 0x44140014, - TMP1075_HANDLER_1 = 0x44420004, - TMP1075_HANDLER_2 = 0x44420005, + TMP1075_HANDLER_TCS_0 = 0x44420004, + TMP1075_HANDLER_TCS_1 = 0x44420005, + TMP1075_HANDLER_PLPCDU_0 = 0x44420006, + TMP1075_HANDLER_PLPCDU_1 = 0x44420007, + TMP1075_HANDLER_IF_BOARD = 0x44420008, + TMP1075_HANDLER_OBC_IF_BOARD = 0x44420009, PCDU_HANDLER = 0x442000A1, P60DOCK_HANDLER = 0x44250000, PDU1_HANDLER = 0x44250001, diff --git a/dummies/TemperatureSensorsDummy.cpp b/dummies/TemperatureSensorsDummy.cpp index c580473a..52190ee8 100644 --- a/dummies/TemperatureSensorsDummy.cpp +++ b/dummies/TemperatureSensorsDummy.cpp @@ -23,8 +23,8 @@ TemperatureSensorsDummy::TemperatureSensorsDummy() ObjectManager::instance()->insert(objects::RTD_13_IC16_PLPCDU_HEATSPREADER, this); ObjectManager::instance()->insert(objects::RTD_14_IC17_TCS_BOARD, this); ObjectManager::instance()->insert(objects::RTD_15_IC18_IMTQ, this); - ObjectManager::instance()->insert(objects::TMP1075_HANDLER_1, this); - ObjectManager::instance()->insert(objects::TMP1075_HANDLER_2, this); + ObjectManager::instance()->insert(objects::TMP1075_HANDLER_TCS_0, this); + ObjectManager::instance()->insert(objects::TMP1075_HANDLER_TCS_1, this); } ReturnValue_t TemperatureSensorsDummy::initialize() { diff --git a/linux/fsfwconfig/devices/addresses.h b/linux/fsfwconfig/devices/addresses.h index ec794490..1395569b 100644 --- a/linux/fsfwconfig/devices/addresses.h +++ b/linux/fsfwconfig/devices/addresses.h @@ -46,8 +46,12 @@ enum logicalAddresses : address_t { enum i2cAddresses : address_t { BPX_BATTERY = 0x07, IMTQ = 0x10, - TMP1075_TCS_1 = 0x48, - TMP1075_TCS_2 = 0x49, + TMP1075_TCS_0 = 0x48, + TMP1075_TCS_1 = 0x49, + TMP1075_PLPCDU_0 = 0x4A, + TMP1075_PLPCDU_1 = 0x4B, + TMP1075_IF_BOARD = 0x4C, + TMP1075_OBC_IF_BOARD = 0x4D }; enum spiAddresses : address_t { diff --git a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index e7f753bd..7b577b26 100644 --- a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -55,30 +55,6 @@ ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) { thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::GET_READ); #endif -#if OBSW_ADD_TMP_DEVICES == 1 - thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0, DeviceHandlerIF::PERFORM_OPERATION); -#endif - -#if OBSW_ADD_TMP_DEVICES == 1 - thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::SEND_WRITE); -#endif - -#if OBSW_ADD_TMP_DEVICES == 1 - thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::GET_WRITE); -#endif - -#if OBSW_ADD_TMP_DEVICES == 1 - thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::SEND_READ); -#endif - -#if OBSW_ADD_TMP_DEVICES == 1 - thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::GET_READ); -#endif #if OBSW_ADD_SUN_SENSORS == 1 @@ -430,28 +406,80 @@ ReturnValue_t pst::pstI2c(FixedTimeslotTaskIF *thisSequence) { uint32_t length = thisSequence->getPeriodMs(); static_cast(length); #if OBSW_ADD_MGT == 1 - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0.2, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::IMTQ_HANDLER, length * 0, DeviceHandlerIF::GET_READ); #endif #if OBSW_ADD_BPX_BATTERY_HANDLER == 1 - thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.2, + DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.2, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.2, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.2, DeviceHandlerIF::GET_READ); +#endif +#if OBSW_ADD_TMP_DEVICES == 1 + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, + DeviceHandlerIF::GET_READ); #endif static_cast(length); return thisSequence->checkSequence(); diff --git a/mission/controller/ThermalController.cpp b/mission/controller/ThermalController.cpp index 66fa2187..603fb0e0 100644 --- a/mission/controller/ThermalController.cpp +++ b/mission/controller/ThermalController.cpp @@ -38,8 +38,8 @@ ThermalController::ThermalController(object_id_t objectId) EiveMax31855::RtdCommands::EXCHANGE_SET_ID), max31865Set14(objects::RTD_14_IC17_TCS_BOARD, EiveMax31855::RtdCommands::EXCHANGE_SET_ID), max31865Set15(objects::RTD_15_IC18_IMTQ, EiveMax31855::RtdCommands::EXCHANGE_SET_ID), - tmp1075Set1(objects::TMP1075_HANDLER_1), - tmp1075Set2(objects::TMP1075_HANDLER_2), + tmp1075Set1(objects::TMP1075_HANDLER_TCS_0), + tmp1075Set2(objects::TMP1075_HANDLER_TCS_1), susSet0(objects::SUS_0_N_LOC_XFYFZM_PT_XF), susSet1(objects::SUS_1_N_LOC_XBYFZM_PT_XB), susSet2(objects::SUS_2_N_LOC_XFYBZB_PT_YB), diff --git a/mission/devices/Tmp1075Handler.cpp b/mission/devices/Tmp1075Handler.cpp index 4b7cff57..1946aa5a 100644 --- a/mission/devices/Tmp1075Handler.cpp +++ b/mission/devices/Tmp1075Handler.cpp @@ -128,6 +128,4 @@ ReturnValue_t Tmp1075Handler::initializeLocalDataPool(localpool::DataPool &local return returnvalue::OK; } -void Tmp1075Handler::setModeNormal() { - setMode(_MODE_TO_NORMAL); -} +void Tmp1075Handler::setModeNormal() { setMode(_MODE_TO_NORMAL); } diff --git a/mission/devices/Tmp1075Handler.h b/mission/devices/Tmp1075Handler.h index 7d0c0fbf..6840db0f 100644 --- a/mission/devices/Tmp1075Handler.h +++ b/mission/devices/Tmp1075Handler.h @@ -21,6 +21,7 @@ class Tmp1075Handler : public DeviceHandlerBase { virtual ~Tmp1075Handler(); void setModeNormal(); + protected: void doStartUp() override; void doShutDown() override; From d4de445112a0f7fe6a3e654873aebe9bef87e7f5 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 11 Nov 2022 16:26:16 +0100 Subject: [PATCH 073/176] update changelog --- CHANGELOG.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 348e7023..33604f09 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -20,6 +20,8 @@ list yields a list of all related PRs for each release. - MAX3185 Low Level Handler and Device Handler: Simplifications and bugfixes to allow switching off without triggering unrequested replies PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/313 +- Add remaining missing TMP1075 device handlers. + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/318 # [v1.15.0] 27.10.2022 From 6261296a0a1362434920e2d7ea56ae7c75b49359 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 11 Nov 2022 17:01:19 +0100 Subject: [PATCH 074/176] there is an issue.. --- bsp_q7s/OBSWConfig.h.in | 1 + .../pollingSequenceFactory.cpp | 94 +++++++++---------- mission/devices/Tmp1075Handler.cpp | 2 +- 3 files changed, 49 insertions(+), 48 deletions(-) diff --git a/bsp_q7s/OBSWConfig.h.in b/bsp_q7s/OBSWConfig.h.in index 840e2575..499d8e6b 100644 --- a/bsp_q7s/OBSWConfig.h.in +++ b/bsp_q7s/OBSWConfig.h.in @@ -104,6 +104,7 @@ #define OBSW_PRINT_CORE_HK 0 #define OBSW_DEBUG_PDU1 0 #define OBSW_DEBUG_PDU2 0 +#define OBSW_DEBUG_TMP1075 0 #define OBSW_DEBUG_GPS 0 #define OBSW_DEBUG_ACU 0 #define OBSW_DEBUG_SYRLINKS 0 diff --git a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index 7b577b26..47245acc 100644 --- a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -427,59 +427,59 @@ ReturnValue_t pst::pstI2c(FixedTimeslotTaskIF *thisSequence) { DeviceHandlerIF::PERFORM_OPERATION); thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE); thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.2, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.2, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.2, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.25, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.25, DeviceHandlerIF::GET_READ); #endif #if OBSW_ADD_TMP_DEVICES == 1 thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::GET_READ); +// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::SEND_WRITE); +// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::GET_WRITE); +// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::SEND_READ); +// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::GET_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, DeviceHandlerIF::GET_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, - DeviceHandlerIF::PERFORM_OPERATION); - thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, - DeviceHandlerIF::SEND_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, - DeviceHandlerIF::GET_WRITE); - thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, - DeviceHandlerIF::SEND_READ); - thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, - DeviceHandlerIF::GET_READ); +// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::SEND_WRITE); +// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::GET_WRITE); +// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::SEND_READ); +// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::GET_READ); +// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, +// DeviceHandlerIF::PERFORM_OPERATION); +// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, +// DeviceHandlerIF::SEND_WRITE); +// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, +// DeviceHandlerIF::GET_WRITE); +// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, +// DeviceHandlerIF::SEND_READ); +// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, DeviceHandlerIF::GET_READ); +// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, +// DeviceHandlerIF::PERFORM_OPERATION); +// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, +// DeviceHandlerIF::SEND_WRITE); +// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, +// DeviceHandlerIF::GET_WRITE); +// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, +// DeviceHandlerIF::SEND_READ); +// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, DeviceHandlerIF::GET_READ); +// thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, +// DeviceHandlerIF::PERFORM_OPERATION); +// thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, +// DeviceHandlerIF::SEND_WRITE); +// thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, +// DeviceHandlerIF::GET_WRITE); +// thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, +// DeviceHandlerIF::SEND_READ); +// thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, DeviceHandlerIF::GET_READ); +// thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, +// DeviceHandlerIF::PERFORM_OPERATION); +// thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, +// DeviceHandlerIF::SEND_WRITE); +// thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, +// DeviceHandlerIF::GET_WRITE); +// thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, +// DeviceHandlerIF::SEND_READ); +// thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, +// DeviceHandlerIF::GET_READ); #endif static_cast(length); return thisSequence->checkSequence(); diff --git a/mission/devices/Tmp1075Handler.cpp b/mission/devices/Tmp1075Handler.cpp index 1946aa5a..56e83ab7 100644 --- a/mission/devices/Tmp1075Handler.cpp +++ b/mission/devices/Tmp1075Handler.cpp @@ -86,7 +86,7 @@ ReturnValue_t Tmp1075Handler::interpretDeviceReply(DeviceCommandId_t id, const u int16_t tempValueRaw = 0; tempValueRaw = packet[0] << 4 | packet[1] >> 4; float tempValue = ((static_cast(tempValueRaw)) * 0.0625); -#if OBSW_VERBOSE_LEVEL >= 1 +#if OBSW_DEBUG_TMP1075 == 1 sif::info << "Tmp1075 with object id: 0x" << std::hex << getObjectId() << ": Temperature: " << tempValue << " °C" << std::endl; #endif From 1a17770bbc827f9661e6c8fceb08de802bebb268 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 11 Nov 2022 18:52:12 +0100 Subject: [PATCH 075/176] all TMP1075 dev except the OBC IF board one working --- bsp_q7s/boardconfig/busConf.h | 3 +- bsp_q7s/core/ObjectFactory.cpp | 9 ++- .../pollingSequenceFactory.cpp | 70 +++++++++---------- 3 files changed, 41 insertions(+), 41 deletions(-) diff --git a/bsp_q7s/boardconfig/busConf.h b/bsp_q7s/boardconfig/busConf.h index 1db53d3e..7b50af4e 100644 --- a/bsp_q7s/boardconfig/busConf.h +++ b/bsp_q7s/boardconfig/busConf.h @@ -8,7 +8,8 @@ static constexpr uint32_t SPI_MAIN_BUS_LOCK_TIMEOUT = 50; static constexpr char SPI_RW_DEV[] = "/dev/spi_rw"; -static constexpr char I2C_DEFAULT_DEV[] = "/dev/i2c_eive"; +static constexpr char I2C_PL_EIVE[] = "/dev/i2c_eive"; +static constexpr char I2C_PS_EIVE[] = "/dev/i2c-2"; static constexpr char UART_GNSS_DEV[] = "/dev/gps0"; static constexpr char UART_PLOC_MPSOC_DEV[] = "/dev/ul_plmpsoc"; diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index f05dfc46..83d6d1c1 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -135,7 +135,7 @@ void ObjectFactory::createTmpComponents() { for (size_t idx = 0; idx < tmpDevIds.size(); idx++) { tmpDevCookies.push_back( - new I2cCookie(tmpDevIds[idx].second, TMP1075::MAX_REPLY_LENGTH, q7s::I2C_DEFAULT_DEV)); + new I2cCookie(tmpDevIds[idx].second, TMP1075::MAX_REPLY_LENGTH, q7s::I2C_PS_EIVE)); auto* tmpDevHandler = new Tmp1075Handler(tmpDevIds[idx].first, objects::I2C_COM_IF, tmpDevCookies[idx]); // TODO: Remove this after TCS subsystem was added @@ -904,7 +904,7 @@ void ObjectFactory::createTestComponents(LinuxLibgpioIF* gpioComIF) { new SpiTestClass(objects::SPI_TEST, gpioComIF); #endif #if OBSW_ADD_I2C_TEST_CODE == 1 - new I2cTestClass(objects::I2C_TEST, q7s::I2C_DEFAULT_DEV); + new I2cTestClass(objects::I2C_TEST, q7s::I2C_PL_EIVE); #endif #if OBSW_ADD_UART_TEST_CODE == 1 // auto* reader= new ScexUartReader(objects::SCEX_UART_READER); @@ -926,8 +926,7 @@ void ObjectFactory::createStrComponents(PowerSwitchIF* pwrSwitcher) { } void ObjectFactory::createImtqComponents(PowerSwitchIF* pwrSwitcher) { - I2cCookie* imtqI2cCookie = - new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE, q7s::I2C_DEFAULT_DEV); + I2cCookie* imtqI2cCookie = new I2cCookie(addresses::IMTQ, IMTQ::MAX_REPLY_SIZE, q7s::I2C_PL_EIVE); auto imtqHandler = new ImtqHandler(objects::IMTQ_HANDLER, objects::I2C_COM_IF, imtqI2cCookie, pcdu::Switches::PDU1_CH3_MGT_5V); imtqHandler->setPowerSwitcher(pwrSwitcher); @@ -943,7 +942,7 @@ void ObjectFactory::createImtqComponents(PowerSwitchIF* pwrSwitcher) { } void ObjectFactory::createBpxBatteryComponent() { - I2cCookie* bpxI2cCookie = new I2cCookie(addresses::BPX_BATTERY, 100, q7s::I2C_DEFAULT_DEV); + I2cCookie* bpxI2cCookie = new I2cCookie(addresses::BPX_BATTERY, 100, q7s::I2C_PL_EIVE); BpxBatteryHandler* bpxHandler = new BpxBatteryHandler(objects::BPX_BATT_HANDLER, objects::I2C_COM_IF, bpxI2cCookie); bpxHandler->setStartUpImmediately(); diff --git a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index 47245acc..cb30ce5a 100644 --- a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -433,43 +433,43 @@ ReturnValue_t pst::pstI2c(FixedTimeslotTaskIF *thisSequence) { #if OBSW_ADD_TMP_DEVICES == 1 thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::PERFORM_OPERATION); -// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::SEND_WRITE); -// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::GET_WRITE); -// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::SEND_READ); -// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::GET_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::PERFORM_OPERATION); -// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::SEND_WRITE); -// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::GET_WRITE); -// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::SEND_READ); -// thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::GET_READ); -// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, -// DeviceHandlerIF::PERFORM_OPERATION); -// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, -// DeviceHandlerIF::SEND_WRITE); -// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, -// DeviceHandlerIF::GET_WRITE); -// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, -// DeviceHandlerIF::SEND_READ); -// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, DeviceHandlerIF::GET_READ); -// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, -// DeviceHandlerIF::PERFORM_OPERATION); -// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, -// DeviceHandlerIF::SEND_WRITE); -// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, -// DeviceHandlerIF::GET_WRITE); -// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, -// DeviceHandlerIF::SEND_READ); -// thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, DeviceHandlerIF::GET_READ); -// thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, -// DeviceHandlerIF::PERFORM_OPERATION); -// thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, -// DeviceHandlerIF::SEND_WRITE); -// thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, -// DeviceHandlerIF::GET_WRITE); -// thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, -// DeviceHandlerIF::SEND_READ); -// thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_1, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_0, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_PLPCDU_1, length * 0.4, DeviceHandlerIF::GET_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, + DeviceHandlerIF::PERFORM_OPERATION); + thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, + DeviceHandlerIF::SEND_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, + DeviceHandlerIF::GET_WRITE); + thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, + DeviceHandlerIF::SEND_READ); + thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, DeviceHandlerIF::GET_READ); // thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, // DeviceHandlerIF::PERFORM_OPERATION); // thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, From ee6bb4df3bdc641eb5c334f0396bf2170029fc75 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 11 Nov 2022 18:56:34 +0100 Subject: [PATCH 076/176] add some informative comments --- linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index cb30ce5a..af7175a3 100644 --- a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -401,6 +401,8 @@ ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) { return thisSequence->checkSequence(); } +// I don't think this needs to be in a PST because linux takes care of bus serialization, but +// keep it like this for now, it works ReturnValue_t pst::pstI2c(FixedTimeslotTaskIF *thisSequence) { // Length of a communication cycle uint32_t length = thisSequence->getPeriodMs(); @@ -430,6 +432,7 @@ ReturnValue_t pst::pstI2c(FixedTimeslotTaskIF *thisSequence) { thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.25, DeviceHandlerIF::SEND_READ); thisSequence->addSlot(objects::BPX_BATT_HANDLER, length * 0.25, DeviceHandlerIF::GET_READ); #endif + // These are actually part of another bus, but this works, so keep it like this for now #if OBSW_ADD_TMP_DEVICES == 1 thisSequence->addSlot(objects::TMP1075_HANDLER_TCS_0, length * 0.4, DeviceHandlerIF::PERFORM_OPERATION); From a855920fb2df88c5ba714e62516c59f399f01bd2 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 14 Nov 2022 09:12:15 +0100 Subject: [PATCH 077/176] README update, I2C addr update --- README.md | 16 ++++++++++++---- bsp_q7s/core/ObjectFactory.cpp | 4 ++-- linux/fsfwconfig/devices/addresses.h | 4 ++-- 3 files changed, 16 insertions(+), 8 deletions(-) diff --git a/README.md b/README.md index 040bc5ed..f68eb210 100644 --- a/README.md +++ b/README.md @@ -1108,11 +1108,19 @@ cat /proc/tty/driver ## I2C -Getting information about I2C device -```` +Getting information about some I2C device + +```sh ls /sys/class/i2c-dev/i2c-0/device/device/driver -```` -This shows the memory mapping of /dev/i2c-0 +``` +This shows the memory mapping of `/dev/i2c-0`. + +You can use the `i2cdetect` utility to scan for I2C devices. +For example, to do this for bus 0 (`/dev/i2c-0`), you can use + +```sh +i2cdetect -r -y 0 +``` ## CAN diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index 83d6d1c1..bc2d7562 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -128,8 +128,8 @@ void ObjectFactory::createTmpComponents() { {objects::TMP1075_HANDLER_TCS_1, addresses::TMP1075_TCS_1}, {objects::TMP1075_HANDLER_PLPCDU_0, addresses::TMP1075_PLPCDU_0}, {objects::TMP1075_HANDLER_PLPCDU_1, addresses::TMP1075_PLPCDU_1}, - {objects::TMP1075_HANDLER_IF_BOARD, addresses::TMP1075_IF_BOARD}, - {objects::TMP1075_HANDLER_OBC_IF_BOARD, addresses::TMP1075_OBC_IF_BOARD}, + {objects::TMP1075_HANDLER_IF_BOARD, addresses::TMP1075_IF_BOARD_0}, + {objects::TMP1075_HANDLER_OBC_IF_BOARD, addresses::TMP1075_IF_BOARD_1}, }}; std::vector tmpDevCookies; diff --git a/linux/fsfwconfig/devices/addresses.h b/linux/fsfwconfig/devices/addresses.h index 1395569b..ce936fcb 100644 --- a/linux/fsfwconfig/devices/addresses.h +++ b/linux/fsfwconfig/devices/addresses.h @@ -50,8 +50,8 @@ enum i2cAddresses : address_t { TMP1075_TCS_1 = 0x49, TMP1075_PLPCDU_0 = 0x4A, TMP1075_PLPCDU_1 = 0x4B, - TMP1075_IF_BOARD = 0x4C, - TMP1075_OBC_IF_BOARD = 0x4D + TMP1075_IF_BOARD_0 = 0x4C, + TMP1075_IF_BOARD_1 = 0x4D }; enum spiAddresses : address_t { From a39ff34a0ab6ead2070098f220973b45abede5ca Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 14 Nov 2022 09:13:20 +0100 Subject: [PATCH 078/176] re-name enum --- linux/fsfwconfig/devices/addresses.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/linux/fsfwconfig/devices/addresses.h b/linux/fsfwconfig/devices/addresses.h index ce936fcb..d87eacb4 100644 --- a/linux/fsfwconfig/devices/addresses.h +++ b/linux/fsfwconfig/devices/addresses.h @@ -43,7 +43,7 @@ enum logicalAddresses : address_t { DUMMY_GPS1 = 131, }; -enum i2cAddresses : address_t { +enum I2cAddress : address_t { BPX_BATTERY = 0x07, IMTQ = 0x10, TMP1075_TCS_0 = 0x48, From d51c088afd39c5c8f26d9028705a23bb8ed2f2f3 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 14 Nov 2022 09:16:17 +0100 Subject: [PATCH 079/176] there is only one tmp1075 left --- bsp_q7s/core/ObjectFactory.cpp | 5 ++--- linux/fsfwconfig/devices/addresses.h | 3 +-- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index bc2d7562..fc9240a0 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -123,13 +123,12 @@ void Factory::setStaticFrameworkObjectIds() { void ObjectFactory::setStatics() { Factory::setStaticFrameworkObjectIds(); } void ObjectFactory::createTmpComponents() { - std::array, 6> tmpDevIds = {{ + std::array, 5> tmpDevIds = {{ {objects::TMP1075_HANDLER_TCS_0, addresses::TMP1075_TCS_0}, {objects::TMP1075_HANDLER_TCS_1, addresses::TMP1075_TCS_1}, {objects::TMP1075_HANDLER_PLPCDU_0, addresses::TMP1075_PLPCDU_0}, {objects::TMP1075_HANDLER_PLPCDU_1, addresses::TMP1075_PLPCDU_1}, - {objects::TMP1075_HANDLER_IF_BOARD, addresses::TMP1075_IF_BOARD_0}, - {objects::TMP1075_HANDLER_OBC_IF_BOARD, addresses::TMP1075_IF_BOARD_1}, + {objects::TMP1075_HANDLER_IF_BOARD, addresses::TMP1075_IF_BOARD}, }}; std::vector tmpDevCookies; diff --git a/linux/fsfwconfig/devices/addresses.h b/linux/fsfwconfig/devices/addresses.h index d87eacb4..d7056307 100644 --- a/linux/fsfwconfig/devices/addresses.h +++ b/linux/fsfwconfig/devices/addresses.h @@ -50,8 +50,7 @@ enum I2cAddress : address_t { TMP1075_TCS_1 = 0x49, TMP1075_PLPCDU_0 = 0x4A, TMP1075_PLPCDU_1 = 0x4B, - TMP1075_IF_BOARD_0 = 0x4C, - TMP1075_IF_BOARD_1 = 0x4D + TMP1075_IF_BOARD = 0x4C, }; enum spiAddresses : address_t { From 31f6a865d3a7f4a7b7d106a0a940096f80612316 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 14 Nov 2022 09:19:34 +0100 Subject: [PATCH 080/176] remove unused code --- .../pollingsequence/pollingSequenceFactory.cpp | 10 ---------- 1 file changed, 10 deletions(-) diff --git a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp index af7175a3..f10043b5 100644 --- a/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp +++ b/linux/fsfwconfig/pollingsequence/pollingSequenceFactory.cpp @@ -473,16 +473,6 @@ ReturnValue_t pst::pstI2c(FixedTimeslotTaskIF *thisSequence) { thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, DeviceHandlerIF::SEND_READ); thisSequence->addSlot(objects::TMP1075_HANDLER_IF_BOARD, length * 0.4, DeviceHandlerIF::GET_READ); -// thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, -// DeviceHandlerIF::PERFORM_OPERATION); -// thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, -// DeviceHandlerIF::SEND_WRITE); -// thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, -// DeviceHandlerIF::GET_WRITE); -// thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, -// DeviceHandlerIF::SEND_READ); -// thisSequence->addSlot(objects::TMP1075_HANDLER_OBC_IF_BOARD, length * 0.4, -// DeviceHandlerIF::GET_READ); #endif static_cast(length); return thisSequence->checkSequence(); From 012590273fe65d18f32c4e9b3688c2c95abcaa37 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 14 Nov 2022 10:04:41 +0100 Subject: [PATCH 081/176] add missing TMP1075 devs in TCS ctrl --- mission/controller/ThermalController.cpp | 65 ++++++++++++++----- mission/controller/ThermalController.h | 7 +- .../ThermalControllerDefinitions.h | 17 +++-- 3 files changed, 67 insertions(+), 22 deletions(-) diff --git a/mission/controller/ThermalController.cpp b/mission/controller/ThermalController.cpp index 603fb0e0..7e5ded8b 100644 --- a/mission/controller/ThermalController.cpp +++ b/mission/controller/ThermalController.cpp @@ -38,8 +38,11 @@ ThermalController::ThermalController(object_id_t objectId) EiveMax31855::RtdCommands::EXCHANGE_SET_ID), max31865Set14(objects::RTD_14_IC17_TCS_BOARD, EiveMax31855::RtdCommands::EXCHANGE_SET_ID), max31865Set15(objects::RTD_15_IC18_IMTQ, EiveMax31855::RtdCommands::EXCHANGE_SET_ID), - tmp1075Set1(objects::TMP1075_HANDLER_TCS_0), - tmp1075Set2(objects::TMP1075_HANDLER_TCS_1), + tmp1075SetTcs0(objects::TMP1075_HANDLER_TCS_0), + tmp1075SetTcs1(objects::TMP1075_HANDLER_TCS_1), + tmp1075SetPlPcdu0(objects::TMP1075_HANDLER_PLPCDU_0), + tmp1075SetPlPcdu1(objects::TMP1075_HANDLER_PLPCDU_1), + tmp1075SetIfBoard(objects::TMP1075_HANDLER_IF_BOARD), susSet0(objects::SUS_0_N_LOC_XFYFZM_PT_XF), susSet1(objects::SUS_1_N_LOC_XBYFZM_PT_XB), susSet2(objects::SUS_2_N_LOC_XFYBZB_PT_YB), @@ -128,9 +131,9 @@ ReturnValue_t ThermalController::initializeLocalDataPool(localpool::DataPool& lo new PoolEntry({14.0})); localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_MAGNETTORQUER, new PoolEntry({15.0})); - localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TMP1075_1, + localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TMP1075_TCS_0, new PoolEntry({15.0})); - localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TMP1075_2, + localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TMP1075_TCS_1, new PoolEntry({15.0})); localDataPoolMap.emplace(thermalControllerDefinitions::SUS_0_N_LOC_XFYFZM_PT_XF, @@ -415,23 +418,53 @@ void ThermalController::copySensors() { } { - PoolReadGuard pg111(&tmp1075Set1, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT); - if (pg111.getReadResult() == returnvalue::OK) { - sensorTemperatures.sensor_tmp1075_1.value = tmp1075Set1.temperatureCelcius.value; - sensorTemperatures.sensor_tmp1075_1.setValid(tmp1075Set1.temperatureCelcius.isValid()); - if (not tmp1075Set1.temperatureCelcius.isValid()) { - sensorTemperatures.sensor_tmp1075_1.value = INVALID_TEMPERATURE; + PoolReadGuard pg(&tmp1075SetTcs0, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT); + if (pg.getReadResult() == returnvalue::OK) { + sensorTemperatures.tmp1075Tcs0.value = tmp1075SetTcs0.temperatureCelcius.value; + sensorTemperatures.tmp1075Tcs0.setValid(tmp1075SetTcs0.temperatureCelcius.isValid()); + if (not tmp1075SetTcs0.temperatureCelcius.isValid()) { + sensorTemperatures.tmp1075Tcs0.value = INVALID_TEMPERATURE; } } } { - PoolReadGuard pg112(&tmp1075Set2, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT); - if (pg112.getReadResult() == returnvalue::OK) { - sensorTemperatures.sensor_tmp1075_2.value = tmp1075Set2.temperatureCelcius.value; - sensorTemperatures.sensor_tmp1075_2.setValid(tmp1075Set2.temperatureCelcius.isValid()); - if (not tmp1075Set2.temperatureCelcius.isValid()) { - sensorTemperatures.sensor_tmp1075_2.value = INVALID_TEMPERATURE; + PoolReadGuard pg(&tmp1075SetTcs1, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT); + if (pg.getReadResult() == returnvalue::OK) { + sensorTemperatures.tmp1075Tcs1.value = tmp1075SetTcs1.temperatureCelcius.value; + sensorTemperatures.tmp1075Tcs1.setValid(tmp1075SetTcs1.temperatureCelcius.isValid()); + if (not tmp1075SetTcs1.temperatureCelcius.isValid()) { + sensorTemperatures.tmp1075Tcs1.value = INVALID_TEMPERATURE; + } + } + } + { + PoolReadGuard pg(&tmp1075SetPlPcdu0, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT); + if (pg.getReadResult() == returnvalue::OK) { + sensorTemperatures.tmp1075PlPcdu0.value = tmp1075SetPlPcdu0.temperatureCelcius.value; + sensorTemperatures.tmp1075PlPcdu0.setValid(tmp1075SetPlPcdu0.temperatureCelcius.isValid()); + if (not tmp1075SetPlPcdu0.temperatureCelcius.isValid()) { + sensorTemperatures.tmp1075PlPcdu0.value = INVALID_TEMPERATURE; + } + } + } + { + PoolReadGuard pg(&tmp1075SetPlPcdu1, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT); + if (pg.getReadResult() == returnvalue::OK) { + sensorTemperatures.tmp1075PlPcdu1.value = tmp1075SetPlPcdu1.temperatureCelcius.value; + sensorTemperatures.tmp1075PlPcdu1.setValid(tmp1075SetPlPcdu1.temperatureCelcius.isValid()); + if (not tmp1075SetPlPcdu1.temperatureCelcius.isValid()) { + sensorTemperatures.tmp1075PlPcdu1.value = INVALID_TEMPERATURE; + } + } + } + { + PoolReadGuard pg(&tmp1075SetIfBoard, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT); + if (pg.getReadResult() == returnvalue::OK) { + sensorTemperatures.tmp1075IfBrd.value = tmp1075SetIfBoard.temperatureCelcius.value; + sensorTemperatures.tmp1075IfBrd.setValid(tmp1075SetIfBoard.temperatureCelcius.isValid()); + if (not tmp1075SetIfBoard.temperatureCelcius.isValid()) { + sensorTemperatures.tmp1075IfBrd.value = INVALID_TEMPERATURE; } } } diff --git a/mission/controller/ThermalController.h b/mission/controller/ThermalController.h index 76366d0c..9fabae71 100644 --- a/mission/controller/ThermalController.h +++ b/mission/controller/ThermalController.h @@ -55,8 +55,11 @@ class ThermalController : public ExtendedControllerBase { MAX31865::Max31865Set max31865Set13; MAX31865::Max31865Set max31865Set14; MAX31865::Max31865Set max31865Set15; - TMP1075::Tmp1075Dataset tmp1075Set1; - TMP1075::Tmp1075Dataset tmp1075Set2; + TMP1075::Tmp1075Dataset tmp1075SetTcs0; + TMP1075::Tmp1075Dataset tmp1075SetTcs1; + TMP1075::Tmp1075Dataset tmp1075SetPlPcdu0; + TMP1075::Tmp1075Dataset tmp1075SetPlPcdu1; + TMP1075::Tmp1075Dataset tmp1075SetIfBoard; // SUS SUS::SusDataset susSet0; diff --git a/mission/controller/controllerdefinitions/ThermalControllerDefinitions.h b/mission/controller/controllerdefinitions/ThermalControllerDefinitions.h index c2824c58..6eaa28e4 100644 --- a/mission/controller/controllerdefinitions/ThermalControllerDefinitions.h +++ b/mission/controller/controllerdefinitions/ThermalControllerDefinitions.h @@ -30,8 +30,11 @@ enum PoolIds : lp_id_t { SENSOR_PLPCDU_HEATSPREADER, SENSOR_TCS_BOARD, SENSOR_MAGNETTORQUER, - SENSOR_TMP1075_1, - SENSOR_TMP1075_2, + SENSOR_TMP1075_TCS_0, + SENSOR_TMP1075_TCS_1, + SENSOR_TMP1075_PLPCDU_0, + SENSOR_TMP1075_PLPCDU_1, + SENSOR_TMP1075_IF_BOARD, SUS_0_N_LOC_XFYFZM_PT_XF, SUS_6_R_LOC_XFYBZM_PT_XF, @@ -111,8 +114,14 @@ class SensorTemperatures : public StaticLocalDataSet sensor_tcs_board = lp_var_t(sid.objectId, PoolIds::SENSOR_TCS_BOARD, this); lp_var_t sensor_magnettorquer = lp_var_t(sid.objectId, PoolIds::SENSOR_MAGNETTORQUER, this); - lp_var_t sensor_tmp1075_1 = lp_var_t(sid.objectId, PoolIds::SENSOR_TMP1075_1, this); - lp_var_t sensor_tmp1075_2 = lp_var_t(sid.objectId, PoolIds::SENSOR_TMP1075_2, this); + lp_var_t tmp1075Tcs0 = lp_var_t(sid.objectId, PoolIds::SENSOR_TMP1075_TCS_0, this); + lp_var_t tmp1075Tcs1 = lp_var_t(sid.objectId, PoolIds::SENSOR_TMP1075_TCS_1, this); + lp_var_t tmp1075PlPcdu0 = + lp_var_t(sid.objectId, PoolIds::SENSOR_TMP1075_PLPCDU_0, this); + lp_var_t tmp1075PlPcdu1 = + lp_var_t(sid.objectId, PoolIds::SENSOR_TMP1075_PLPCDU_1, this); + lp_var_t tmp1075IfBrd = + lp_var_t(sid.objectId, PoolIds::SENSOR_TMP1075_IF_BOARD, this); }; /** From 876c2b36bfb4822938b1391bd07bea8e68a7f334 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 14 Nov 2022 10:11:44 +0100 Subject: [PATCH 082/176] add missing tmp devs in ctrel map as well --- mission/controller/ThermalController.cpp | 9 +++++---- mission/controller/ThermalController.h | 6 ++++++ 2 files changed, 11 insertions(+), 4 deletions(-) diff --git a/mission/controller/ThermalController.cpp b/mission/controller/ThermalController.cpp index 7e5ded8b..45f26f8b 100644 --- a/mission/controller/ThermalController.cpp +++ b/mission/controller/ThermalController.cpp @@ -131,10 +131,11 @@ ReturnValue_t ThermalController::initializeLocalDataPool(localpool::DataPool& lo new PoolEntry({14.0})); localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_MAGNETTORQUER, new PoolEntry({15.0})); - localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TMP1075_TCS_0, - new PoolEntry({15.0})); - localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TMP1075_TCS_1, - new PoolEntry({15.0})); + localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TMP1075_TCS_0, &tmp1075Tcs0); + localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TMP1075_TCS_1, &tmp1075Tcs1); + localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TMP1075_PLPCDU_0, &tmp1075PlPcdu0); + localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TMP1075_PLPCDU_1, &tmp1075PlPcdu1); + localDataPoolMap.emplace(thermalControllerDefinitions::SENSOR_TMP1075_IF_BOARD, &tmp1075IfBrd); localDataPoolMap.emplace(thermalControllerDefinitions::SUS_0_N_LOC_XFYFZM_PT_XF, new PoolEntry({0.0})); diff --git a/mission/controller/ThermalController.h b/mission/controller/ThermalController.h index 9fabae71..5071d811 100644 --- a/mission/controller/ThermalController.h +++ b/mission/controller/ThermalController.h @@ -78,6 +78,12 @@ class ThermalController : public ExtendedControllerBase { // Initial delay to make sure all pool variables have been initialized their owners Countdown initialCountdown = Countdown(DELAY); + PoolEntry tmp1075Tcs0 = PoolEntry(10.0); + PoolEntry tmp1075Tcs1 = PoolEntry(10.0); + PoolEntry tmp1075PlPcdu0 = PoolEntry(10.0); + PoolEntry tmp1075PlPcdu1 = PoolEntry(10.0); + PoolEntry tmp1075IfBrd = PoolEntry(10.0); + static constexpr dur_millis_t MUTEX_TIMEOUT = 50; void copySensors(); void copySus(); From 0d08a282b4652955fe6cf426163ce383d56ab9fc Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 14 Nov 2022 17:05:46 +0100 Subject: [PATCH 083/176] fix for set capacity --- .../controllerdefinitions/ThermalControllerDefinitions.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mission/controller/controllerdefinitions/ThermalControllerDefinitions.h b/mission/controller/controllerdefinitions/ThermalControllerDefinitions.h index 6eaa28e4..9f800bec 100644 --- a/mission/controller/controllerdefinitions/ThermalControllerDefinitions.h +++ b/mission/controller/controllerdefinitions/ThermalControllerDefinitions.h @@ -78,7 +78,7 @@ enum PoolIds : lp_id_t { TEMP_ADC_PAYLOAD_PCDU }; -static const uint8_t ENTRIES_SENSOR_TEMPERATURE_SET = 18; +static const uint8_t ENTRIES_SENSOR_TEMPERATURE_SET = 25; static const uint8_t ENTRIES_DEVICE_TEMPERATURE_SET = 25; static const uint8_t ENTRIES_SUS_TEMPERATURE_SET = 12; From 89af06a3109881899f0ed37b84b3f8c4b4e66bbc Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 14 Nov 2022 17:10:41 +0100 Subject: [PATCH 084/176] update object list --- generators/bsp_q7s_objects.csv | 8 +++++-- generators/events/translateEvents.cpp | 2 +- generators/objects/translateObjects.cpp | 24 ++++++++++++++----- linux/fsfwconfig/events/translateEvents.cpp | 2 +- linux/fsfwconfig/objects/translateObjects.cpp | 24 ++++++++++++++----- tmtc | 2 +- 6 files changed, 45 insertions(+), 17 deletions(-) diff --git a/generators/bsp_q7s_objects.csv b/generators/bsp_q7s_objects.csv index 10ac10ed..bca5b872 100644 --- a/generators/bsp_q7s_objects.csv +++ b/generators/bsp_q7s_objects.csv @@ -50,8 +50,12 @@ 0x44330032;SCEX 0x444100A2;SOLAR_ARRAY_DEPL_HANDLER 0x444100A4;HEATER_HANDLER -0x44420004;TMP1075_HANDLER_1 -0x44420005;TMP1075_HANDLER_2 +0x44420004;TMP1075_HANDLER_TCS_0 +0x44420005;TMP1075_HANDLER_TCS_1 +0x44420006;TMP1075_HANDLER_PLPCDU_0 +0x44420007;TMP1075_HANDLER_PLPCDU_1 +0x44420008;TMP1075_HANDLER_IF_BOARD +0x44420009;TMP1075_HANDLER_OBC_IF_BOARD 0x44420016;RTD_0_IC3_PLOC_HEATSPREADER 0x44420017;RTD_1_IC4_PLOC_MISSIONBOARD 0x44420018;RTD_2_IC5_4K_CAMERA diff --git a/generators/events/translateEvents.cpp b/generators/events/translateEvents.cpp index 87c790d7..ee85e05c 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** * @brief Auto-generated event translation file. Contains 234 translations. * @details - * Generated on: 2022-11-10 18:07:26 + * Generated on: 2022-11-14 17:10:10 */ #include "translateEvents.h" diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index cfb7f9a5..96a2d656 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -1,8 +1,8 @@ /** * @brief Auto-generated object translation file. * @details - * Contains 144 translations. - * Generated on: 2022-11-10 18:07:26 + * Contains 148 translations. + * Generated on: 2022-11-14 17:10:10 */ #include "translateObjects.h" @@ -58,8 +58,12 @@ 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_1_STRING = "TMP1075_HANDLER_1"; -const char *TMP1075_HANDLER_2_STRING = "TMP1075_HANDLER_2"; +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"; @@ -258,9 +262,17 @@ const char *translateObject(object_id_t object) { case 0x444100A4: return HEATER_HANDLER_STRING; case 0x44420004: - return TMP1075_HANDLER_1_STRING; + return TMP1075_HANDLER_TCS_0_STRING; case 0x44420005: - return TMP1075_HANDLER_2_STRING; + 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: diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index 87c790d7..ee85e05c 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. * @details - * Generated on: 2022-11-10 18:07:26 + * Generated on: 2022-11-14 17:10:10 */ #include "translateEvents.h" diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index cfb7f9a5..96a2d656 100644 --- a/linux/fsfwconfig/objects/translateObjects.cpp +++ b/linux/fsfwconfig/objects/translateObjects.cpp @@ -1,8 +1,8 @@ /** * @brief Auto-generated object translation file. * @details - * Contains 144 translations. - * Generated on: 2022-11-10 18:07:26 + * Contains 148 translations. + * Generated on: 2022-11-14 17:10:10 */ #include "translateObjects.h" @@ -58,8 +58,12 @@ 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_1_STRING = "TMP1075_HANDLER_1"; -const char *TMP1075_HANDLER_2_STRING = "TMP1075_HANDLER_2"; +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"; @@ -258,9 +262,17 @@ const char *translateObject(object_id_t object) { case 0x444100A4: return HEATER_HANDLER_STRING; case 0x44420004: - return TMP1075_HANDLER_1_STRING; + return TMP1075_HANDLER_TCS_0_STRING; case 0x44420005: - return TMP1075_HANDLER_2_STRING; + 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: diff --git a/tmtc b/tmtc index 89285ad5..66a1362e 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 89285ad511ef11582b67b307c3840a09efd0577a +Subproject commit 66a1362e7e977e427a66fd3176a9e7b6bc1b5998 From 5690e35a58dd13a05bb2a363c8db804910a72b77 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 09:55:23 +0100 Subject: [PATCH 085/176] bump fsfw --- fsfw | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fsfw b/fsfw index e03e7f52..00284510 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit e03e7f5260eb92d1903188c5ea14ea01616600ae +Subproject commit 002845108d24abe9fbb26618f004f04ccb160938 From 6c568102337c680fc0e7d6e8266016d1586f9421 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 09:55:38 +0100 Subject: [PATCH 086/176] bump fsfw --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 66a1362e..89285ad5 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 66a1362e7e977e427a66fd3176a9e7b6bc1b5998 +Subproject commit 89285ad511ef11582b67b307c3840a09efd0577a From f6729cb3b45c4c7b3a7ea7b081615bf03a09353f Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 13:20:12 +0100 Subject: [PATCH 087/176] bump deps --- fsfw | 2 +- tmtc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/fsfw b/fsfw index 00284510..c5f91926 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 002845108d24abe9fbb26618f004f04ccb160938 +Subproject commit c5f91926c95a8db0c7921176aa3f62cc2bebef47 diff --git a/tmtc b/tmtc index 89285ad5..66a1362e 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 89285ad511ef11582b67b307c3840a09efd0577a +Subproject commit 66a1362e7e977e427a66fd3176a9e7b6bc1b5998 From 9da5a55ef31b3bfdde4239f0c94bf148e3c6a57c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 13:32:05 +0100 Subject: [PATCH 088/176] lets see if that works --- CMakeLists.txt | 7 +++++-- bsp_linux_board/CMakeLists.txt | 1 + linux/CMakeLists.txt | 5 ++++- linux/InitMission.cpp | 1 + linux/boardtest/SpiTestClass.cpp | 27 ++++++++++++++++----------- linux/boardtest/UartTestClass.cpp | 3 ++- 6 files changed, 29 insertions(+), 15 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index ddf101a4..97b7601c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -233,7 +233,7 @@ set(LIB_ARCSEC_PATH ${THIRD_PARTY_FOLDER}/arcsec_star_tracker) set(LIB_JSON_PATH ${THIRD_PARTY_FOLDER}/json) set(FSFW_WARNING_SHADOW_LOCAL_GCC OFF) -set(EIVE_ADD_LINUX_FILES False) +set(EIVE_ADD_LINUX_FILES OFF) # Analyse different OS and architecture/target options, determine BSP_PATH, # display information about compiler etc. @@ -253,12 +253,15 @@ if(TGT_BSP) set(FSFW_CONFIG_PATH "linux/fsfwconfig") if(NOT BUILD_Q7S_SIMPLE_MODE) set(EIVE_ADD_LINUX_FILES TRUE) + set(EIVE_ADD_LINUX_FSFWCONFIG TRUE) set(ADD_GOMSPACE_CSP TRUE) set(ADD_GOMSPACE_CLIENTS TRUE) set(FSFW_HAL_ADD_LINUX ON) set(FSFW_HAL_LINUX_ADD_LIBGPIOD ON) set(FSFW_HAL_LINUX_ADD_PERIPHERAL_DRIVERS ON) endif() + elseif(UNIX) + set(EIVE_ADD_LINUX_FILES ON) endif() if(TGT_BSP MATCHES "arm/raspberrypi") @@ -393,7 +396,7 @@ if(EIVE_ADD_JSON_LIB) add_subdirectory(${LIB_JSON_PATH}) endif() -add_subdirectory(thirdparty/rapidcsv) +add_subdirectory(thirdparty) if(EIVE_ADD_LINUX_FILES) add_subdirectory(${LIB_ARCSEC_PATH}) diff --git a/bsp_linux_board/CMakeLists.txt b/bsp_linux_board/CMakeLists.txt index c1817ac1..39f06401 100644 --- a/bsp_linux_board/CMakeLists.txt +++ b/bsp_linux_board/CMakeLists.txt @@ -3,3 +3,4 @@ target_sources(${OBSW_NAME} PUBLIC InitMission.cpp main.cpp gpioInit.cpp add_subdirectory(boardconfig) add_subdirectory(boardtest) +add_subdirectory(fsfwconfig) diff --git a/linux/CMakeLists.txt b/linux/CMakeLists.txt index d7e6ca93..f8c8935f 100644 --- a/linux/CMakeLists.txt +++ b/linux/CMakeLists.txt @@ -3,7 +3,10 @@ add_subdirectory(utility) add_subdirectory(callbacks) add_subdirectory(boardtest) add_subdirectory(devices) -add_subdirectory(fsfwconfig) add_subdirectory(ipcore) +if(EIVE_ADD_LINUX_FSFWCONFIG) + add_subdirectory(fsfwconfig) +endif() + target_sources(${OBSW_NAME} PUBLIC ObjectFactory.cpp InitMission.cpp) diff --git a/linux/InitMission.cpp b/linux/InitMission.cpp index 5bc8698c..4b7dc1f1 100644 --- a/linux/InitMission.cpp +++ b/linux/InitMission.cpp @@ -6,6 +6,7 @@ #include "OBSWConfig.h" #include "ObjectFactory.h" +#include "eive/objects.h" void scheduling::schedulingScex(TaskFactory& factory, PeriodicTaskIF*& scexDevHandler, PeriodicTaskIF*& scexReaderTask) { diff --git a/linux/boardtest/SpiTestClass.cpp b/linux/boardtest/SpiTestClass.cpp index dc5a5e3b..91e8893c 100644 --- a/linux/boardtest/SpiTestClass.cpp +++ b/linux/boardtest/SpiTestClass.cpp @@ -333,14 +333,12 @@ void SpiTestClass::performPeriodicMax1227Test() { } void SpiTestClass::performMax1227Test() { + std::string deviceName = ""; #ifdef XIPHOS_Q7S - std::string deviceName = q7s::SPI_DEFAULT_DEV; + deviceName = q7s::SPI_DEFAULT_DEV; #elif defined(RASPBERRY_PI) - std::string deviceName = ""; #elif defined(EGSE) - std::string deviceName = ""; #elif defined(TE0720_1CFA) - std::string deviceName = ""; #endif int fd = 0; UnixFileGuard fileHelper(deviceName, &fd, O_RDWR, "SpiComIF::initializeInterface"); @@ -381,8 +379,9 @@ void SpiTestClass::max1227RadSensorTest(int fd) { DiffSel::NONE_0); spiTransferStruct[0].len = 1; transfer(fd, gpioIds::CS_RAD_SENSOR); - max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), 7, spiTransferStruct[0].len); - size_t tmpLen = spiTransferStruct[0].len; + size_t tmpSz = spiTransferStruct[0].len; + max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), 7, tmpSz); + size_t tmpLen = tmpSz; spiTransferStruct[0].len = 1; transfer(fd, gpioIds::CS_RAD_SENSOR); std::memcpy(sendBuffer.data(), sendBuffer.data() + 1, tmpLen - 1); @@ -403,7 +402,8 @@ void SpiTestClass::max1227RadSensorTest(int fd) { for (int idx = 0; idx < 8; idx++) { sif::info << "ADC raw " << idx << ": " << adcRaw[idx] << std::endl; } - max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data(), spiTransferStruct[0].len); + tmpSz = spiTransferStruct[0].len; + max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data(), tmpSz); spiTransferStruct[0].len = 1; transfer(fd, gpioIds::CS_RAD_SENSOR); usleep(65); @@ -467,7 +467,8 @@ void SpiTestClass::max1227SusTest(int fd, SusTestCfg &cfg) { spiTransferStruct[0].len = 1; transfer(fd, cfg.gpioId); - max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), 5, spiTransferStruct[0].len); + size_t tmpSz = spiTransferStruct[0].len; + max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), 5, tmpSz); transfer(fd, cfg.gpioId); uint16_t adcRaw[6] = {}; adcRaw[0] = (recvBuffer[1] << 8) | recvBuffer[2]; @@ -552,7 +553,9 @@ void SpiTestClass::max1227PlPcduTest(int fd) { spiTransferStruct[0].len = 1; transfer(fd, gpioIds::PLPCDU_ADC_CS); uint8_t n = 11; - max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), n, spiTransferStruct[0].len); + size_t tmpSz = spiTransferStruct[0].len; + max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), n, tmpSz); + spiTransferStruct[0].len = tmpSz; size_t dummy = 0; max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data() + spiTransferStruct[0].len, dummy); @@ -585,9 +588,11 @@ void SpiTestClass::max1227PlPcduTest(int fd) { spiTransferStruct[0].len = 1; transfer(fd, gpioIds::PLPCDU_ADC_CS); uint8_t n = 11; - max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), n, spiTransferStruct[0].len); + size_t tmpLen = spiTransferStruct[0].len; + max1227::prepareExternallyClockedRead0ToN(sendBuffer.data(), n, tmpLen); max1227::prepareExternallyClockedTemperatureRead(sendBuffer.data() + spiTransferStruct[0].len, - spiTransferStruct[0].len); + tmpLen); + spiTransferStruct[0].len = tmpLen; transfer(fd, gpioIds::PLPCDU_ADC_CS); uint16_t adcRaw[n + 1] = {}; for (uint8_t idx = 0; idx < n + 1; idx++) { diff --git a/linux/boardtest/UartTestClass.cpp b/linux/boardtest/UartTestClass.cpp index 51ea237f..1f707c8f 100644 --- a/linux/boardtest/UartTestClass.cpp +++ b/linux/boardtest/UartTestClass.cpp @@ -13,6 +13,7 @@ #include #include "OBSWConfig.h" +#include "eive/objects.h" #include "fsfw/globalfunctions/CRC.h" #include "fsfw/globalfunctions/DleEncoder.h" #include "fsfw/globalfunctions/arrayprinter.h" @@ -164,7 +165,7 @@ void UartTestClass::scexInit() { #else std::string devname = "/dev/ul-scex"; #endif - uartCookie = new SerialCookie(this->getObjectId(), devname, UartBaudRate::RATE_57600, 4096); + uartCookie = new UartCookie(this->getObjectId(), devname, UartBaudRate::RATE_57600, 4096); reader->setDebugMode(false); ReturnValue_t result = reader->initializeInterface(uartCookie); if (result != OK) { From 478e3b92374d67279d4092232ca27ef880a271fa Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 13:33:53 +0100 Subject: [PATCH 089/176] add thirdparty CMakeLists.txt --- thirdparty/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) create mode 100644 thirdparty/CMakeLists.txt diff --git a/thirdparty/CMakeLists.txt b/thirdparty/CMakeLists.txt new file mode 100644 index 00000000..68ea851d --- /dev/null +++ b/thirdparty/CMakeLists.txt @@ -0,0 +1 @@ +add_subdirectory(rapidcsv) From 3c469e5c7a1ab5a1f9d7f42213d61b03f8fe258a Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 13:35:18 +0100 Subject: [PATCH 090/176] uart test class tweak --- linux/boardtest/UartTestClass.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/linux/boardtest/UartTestClass.cpp b/linux/boardtest/UartTestClass.cpp index 1f707c8f..def7da8b 100644 --- a/linux/boardtest/UartTestClass.cpp +++ b/linux/boardtest/UartTestClass.cpp @@ -165,7 +165,7 @@ void UartTestClass::scexInit() { #else std::string devname = "/dev/ul-scex"; #endif - uartCookie = new UartCookie(this->getObjectId(), devname, UartBaudRate::RATE_57600, 4096); + uartCookie = new SerialCookie(this->getObjectId(), devname, UartBaudRate::RATE_57600, 4096); reader->setDebugMode(false); ReturnValue_t result = reader->initializeInterface(uartCookie); if (result != OK) { From 7384c5ce16d4d104b00b7b7e602a7f54cc11ae65 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 13:41:39 +0100 Subject: [PATCH 091/176] update changelog --- CHANGELOG.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 33604f09..acef9e92 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -10,6 +10,8 @@ list yields a list of all related PRs for each release. # [unreleased] +- It is now possible to compile Linux components for the hosted build conditionally + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/322 - ACS Subsystem. PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/231 - Payload Subsystem. PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/231 - Add IRQ mode for PDEC handler. PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/310 From cf57be14bc6007428295ce78cd221d2c6a5ede52 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 16:00:32 +0100 Subject: [PATCH 092/176] assign name for hosted ploc supv --- bsp_hosted/ObjectFactory.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index 7e7bda14..7289c361 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -93,7 +93,7 @@ void ObjectFactory::produce(void* args) { objects::PLOC_SUPERVISOR_HANDLER); #endif /* OBSW_ADD_PLOC_MPSOC == 1 */ #if OBSW_ADD_PLOC_SUPERVISOR == 1 - std::string plocSupvString = ""; + std::string plocSupvString = "/dev/ploc_supv"; auto supervisorCookie = new UartCookie(objects::PLOC_SUPERVISOR_HANDLER, plocSupvString, uart::PLOC_SUPV_BAUD, supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL); From 9ee969218cf7ea993fcd96989cbba7bdde3585b4 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 16:06:23 +0100 Subject: [PATCH 093/176] add README entry for udevadm usage --- README.md | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) 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 From 7d7efaca426bd0909d891ad82a3d9840873c07df Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 16:44:07 +0100 Subject: [PATCH 094/176] improve hosted SW --- bsp_hosted/OBSWConfig.h.in | 8 ++++++++ bsp_hosted/ObjectFactory.cpp | 6 ++---- bsp_q7s/OBSWConfig.h.in | 7 +++++++ common/config/commonConfig.h.in | 6 ------ dummies/TemperatureSensorsDummy.cpp | 4 ++++ mission/core/GenericFactory.cpp | 12 ++++++------ 6 files changed, 27 insertions(+), 16 deletions(-) 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 7289c361..01d6da22 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -64,10 +64,10 @@ 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; } @@ -107,8 +107,6 @@ void ObjectFactory::produce(void* args) { dummy::DummyCfg cfg; dummy::createDummies(cfg); - new TemperatureSensorsDummy(); - new SusDummy(); new ThermalController(objects::THERMAL_CONTROLLER); new TestTask(objects::TEST_TASK); } 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/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/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/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); From f96d831cc92d2f55e808063f2786f17162e320c9 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 16:46:47 +0100 Subject: [PATCH 095/176] simiplify hosted SW --- bsp_hosted/InitMission.cpp | 20 ++++++++------------ 1 file changed, 8 insertions(+), 12 deletions(-) diff --git a/bsp_hosted/InitMission.cpp b/bsp_hosted/InitMission.cpp index 4ee90f70..1301ff51 100644 --- a/bsp_hosted/InitMission.cpp +++ b/bsp_hosted/InitMission.cpp @@ -53,28 +53,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); @@ -174,8 +171,7 @@ void initmission::initTasks() { #endif /* OBSW_ADD_TEST_CODE == 1 */ sif::info << "Starting tasks.." << std::endl; - tmTcDistributor->startTask(); - tmtcBridgeTask->startTask(); + tmtcDistributor->startTask(); tmtcPollingTask->startTask(); pusVerification->startTask(); From b9f4a7be0ce186796adfbcf0bbfecce99a233b2d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 16:59:33 +0100 Subject: [PATCH 096/176] dumb undefined reference --- bsp_hosted/InitMission.cpp | 13 +++++++++++++ bsp_hosted/InitMission.h | 5 +---- linux/InitMission.h | 1 + 3 files changed, 15 insertions(+), 4 deletions(-) diff --git a/bsp_hosted/InitMission.cpp b/bsp_hosted/InitMission.cpp index 1301ff51..a10d2f79 100644 --- a/bsp_hosted/InitMission.cpp +++ b/bsp_hosted/InitMission.cpp @@ -10,6 +10,7 @@ #include #include #include +#include "linux/InitMission.h" #include @@ -163,6 +164,18 @@ 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", 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); + } +#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) { diff --git a/bsp_hosted/InitMission.h b/bsp_hosted/InitMission.h index 507de592..41da5db2 100644 --- a/bsp_hosted/InitMission.h +++ b/bsp_hosted/InitMission.h @@ -1,9 +1,6 @@ -#ifndef BSP_LINUX_INITMISSION_H_ -#define BSP_LINUX_INITMISSION_H_ +#pragma once namespace initmission { void initMission(); void initTasks(); }; // namespace initmission - -#endif /* BSP_LINUX_INITMISSION_H_ */ diff --git a/linux/InitMission.h b/linux/InitMission.h index dd809ff7..b5ffc415 100644 --- a/linux/InitMission.h +++ b/linux/InitMission.h @@ -1,4 +1,5 @@ #pragma once + #include namespace scheduling { From 99f92a87da7eaf127f21ea9c30729c8c0d91091b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 17:03:46 +0100 Subject: [PATCH 097/176] rename scheduling file --- bsp_hosted/InitMission.cpp | 37 +++++++++++------------ bsp_hosted/InitMission.h | 2 +- bsp_hosted/main.cpp | 2 +- linux/CMakeLists.txt | 2 +- linux/{InitMission.cpp => scheduling.cpp} | 4 +-- linux/{InitMission.h => scheduling.h} | 0 mission/utility/InitMission.h | 2 +- 7 files changed, 24 insertions(+), 25 deletions(-) rename linux/{InitMission.cpp => scheduling.cpp} (98%) rename linux/{InitMission.h => scheduling.h} (100%) diff --git a/bsp_hosted/InitMission.cpp b/bsp_hosted/InitMission.cpp index a10d2f79..016985f4 100644 --- a/bsp_hosted/InitMission.cpp +++ b/bsp_hosted/InitMission.cpp @@ -10,10 +10,9 @@ #include #include #include -#include "linux/InitMission.h" - #include +#include "../linux/scheduling.h" #include "ObjectFactory.h" #ifdef LINUX @@ -30,7 +29,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); @@ -41,7 +40,7 @@ void initmission::initMission() { initTasks(); } -void initmission::initTasks() { +void scheduling::initTasks() { TaskFactory* factory = TaskFactory::instance(); if (factory == nullptr) { /* Should never happen ! */ @@ -92,69 +91,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( @@ -169,7 +168,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 */ @@ -179,7 +178,7 @@ void initmission::initTasks() { #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 */ diff --git a/bsp_hosted/InitMission.h b/bsp_hosted/InitMission.h index 41da5db2..e1ba3a4a 100644 --- a/bsp_hosted/InitMission.h +++ b/bsp_hosted/InitMission.h @@ -1,6 +1,6 @@ #pragma once -namespace initmission { +namespace scheduling { void initMission(); void initTasks(); }; // namespace initmission diff --git a/bsp_hosted/main.cpp b/bsp_hosted/main.cpp index e493c1c9..0e1fc01c 100644 --- a/bsp_hosted/main.cpp +++ b/bsp_hosted/main.cpp @@ -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/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/InitMission.cpp b/linux/scheduling.cpp similarity index 98% rename from linux/InitMission.cpp rename to linux/scheduling.cpp index 4b7dc1f1..9a4c1a93 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; diff --git a/linux/InitMission.h b/linux/scheduling.h similarity index 100% rename from linux/InitMission.h rename to linux/scheduling.h diff --git a/mission/utility/InitMission.h b/mission/utility/InitMission.h index 5529f749..c0663544 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 From 9481cc2eb05c2df35cd4fcc039f09c593e042fff Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 17:08:10 +0100 Subject: [PATCH 098/176] rename bsp hosted scheduling file --- bsp_hosted/CMakeLists.txt | 2 +- bsp_hosted/main.cpp | 2 +- bsp_hosted/{InitMission.cpp => scheduling.cpp} | 10 +++++----- bsp_hosted/{InitMission.h => scheduling.h} | 0 4 files changed, 7 insertions(+), 7 deletions(-) rename bsp_hosted/{InitMission.cpp => scheduling.cpp} (99%) rename bsp_hosted/{InitMission.h => scheduling.h} (100%) 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/main.cpp b/bsp_hosted/main.cpp index 0e1fc01c..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"; diff --git a/bsp_hosted/InitMission.cpp b/bsp_hosted/scheduling.cpp similarity index 99% rename from bsp_hosted/InitMission.cpp rename to bsp_hosted/scheduling.cpp index 016985f4..bb50530b 100644 --- a/bsp_hosted/InitMission.cpp +++ b/bsp_hosted/scheduling.cpp @@ -1,6 +1,8 @@ -#include "InitMission.h" +#include "linux/scheduling.h" +#include "scheduling.h" +#include "ObjectFactory.h" +#include "OBSWConfig.h" -#include #include #include #include @@ -10,10 +12,8 @@ #include #include #include -#include -#include "../linux/scheduling.h" -#include "ObjectFactory.h" +#include #ifdef LINUX ServiceInterfaceStream sif::debug("DEBUG"); diff --git a/bsp_hosted/InitMission.h b/bsp_hosted/scheduling.h similarity index 100% rename from bsp_hosted/InitMission.h rename to bsp_hosted/scheduling.h From 23cfe3aa69b575c950b652d7ffb29d38ac30aeb1 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 17:15:14 +0100 Subject: [PATCH 099/176] unbelievable --- bsp_hosted/scheduling.cpp | 2 +- bsp_hosted/scheduling.h | 5 ++++- linux/scheduling.h | 6 ++++-- 3 files changed, 9 insertions(+), 4 deletions(-) diff --git a/bsp_hosted/scheduling.cpp b/bsp_hosted/scheduling.cpp index bb50530b..20b8ba9c 100644 --- a/bsp_hosted/scheduling.cpp +++ b/bsp_hosted/scheduling.cpp @@ -174,7 +174,7 @@ void scheduling::initTasks() { PeriodicTaskIF* plTask = factory->createPeriodicTask( "PL_TASK", 25, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc); - scheduling::addMpsocSupvHandlers(plTask); + //scheduling::addMpsocSupvHandlers(plTask); #if OBSW_ADD_TEST_CODE == 1 result = testTask->addComponent(objects::TEST_TASK); if (result != returnvalue::OK) { diff --git a/bsp_hosted/scheduling.h b/bsp_hosted/scheduling.h index e1ba3a4a..fabec0ce 100644 --- a/bsp_hosted/scheduling.h +++ b/bsp_hosted/scheduling.h @@ -1,6 +1,9 @@ -#pragma once +#ifndef _BSP_HOSTED_SCHEDULING_H_ +#define _BSP_HOSTED_SCHEDULING_H_ namespace scheduling { void initMission(); void initTasks(); }; // namespace initmission + +#endif diff --git a/linux/scheduling.h b/linux/scheduling.h index b5ffc415..ef15cd23 100644 --- a/linux/scheduling.h +++ b/linux/scheduling.h @@ -1,4 +1,5 @@ -#pragma once +#ifndef _LINUX_SCHEDULING_H +#define _LINUX_SCHEDULING_H #include @@ -6,5 +7,6 @@ namespace scheduling { void schedulingScex(TaskFactory& factory, PeriodicTaskIF*& scexDevHandler, PeriodicTaskIF*& scexReaderTask); void addMpsocSupvHandlers(PeriodicTaskIF* task); - } // namespace scheduling + +#endif From e5ec8a74901f586b569cfd994f3a59c7efbe7c0f Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 17:21:12 +0100 Subject: [PATCH 100/176] now the linux files are compiling --- CMakeLists.txt | 3 +++ bsp_hosted/scheduling.cpp | 9 +++++---- bsp_hosted/scheduling.h | 2 +- linux/devices/ploc/PlocSupvUartMan.cpp | 2 +- mission/utility/InitMission.h | 2 +- 5 files changed, 11 insertions(+), 7 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 97b7601c..0753ea9f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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/bsp_hosted/scheduling.cpp b/bsp_hosted/scheduling.cpp index 20b8ba9c..9c239eb3 100644 --- a/bsp_hosted/scheduling.cpp +++ b/bsp_hosted/scheduling.cpp @@ -1,7 +1,4 @@ #include "linux/scheduling.h" -#include "scheduling.h" -#include "ObjectFactory.h" -#include "OBSWConfig.h" #include #include @@ -15,6 +12,10 @@ #include +#include "OBSWConfig.h" +#include "ObjectFactory.h" +#include "scheduling.h" + #ifdef LINUX ServiceInterfaceStream sif::debug("DEBUG"); ServiceInterfaceStream sif::info("INFO"); @@ -174,7 +175,7 @@ void scheduling::initTasks() { PeriodicTaskIF* plTask = factory->createPeriodicTask( "PL_TASK", 25, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc); - //scheduling::addMpsocSupvHandlers(plTask); + scheduling::addMpsocSupvHandlers(plTask); #if OBSW_ADD_TEST_CODE == 1 result = testTask->addComponent(objects::TEST_TASK); if (result != returnvalue::OK) { diff --git a/bsp_hosted/scheduling.h b/bsp_hosted/scheduling.h index fabec0ce..2f98ade2 100644 --- a/bsp_hosted/scheduling.h +++ b/bsp_hosted/scheduling.h @@ -4,6 +4,6 @@ namespace scheduling { void initMission(); void initTasks(); -}; // namespace initmission +}; // namespace scheduling #endif diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 26da089b..3189cb65 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -42,7 +42,7 @@ PlocSupvHelper::PlocSupvHelper(object_id_t objectId) PlocSupvHelper::~PlocSupvHelper() = default; ReturnValue_t PlocSupvHelper::initializeInterface(CookieIF* cookie) { - UartCookie* uartCookie = dynamic_cast(cookie); + auto* uartCookie = dynamic_cast(cookie); if (uartCookie == nullptr) { return FAILED; } diff --git a/mission/utility/InitMission.h b/mission/utility/InitMission.h index c0663544..85d8ae21 100644 --- a/mission/utility/InitMission.h +++ b/mission/utility/InitMission.h @@ -16,4 +16,4 @@ static void printAddObjectError(const char* name, object_id_t objectId) { #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ } -} // namespace initmission +} // namespace scheduling From 7fb689b45159fbe94c7c2f182eaa223a282d4497 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 17:22:28 +0100 Subject: [PATCH 101/176] it was not the #pragma once --- bsp_hosted/scheduling.h | 5 +---- linux/scheduling.h | 5 +---- 2 files changed, 2 insertions(+), 8 deletions(-) diff --git a/bsp_hosted/scheduling.h b/bsp_hosted/scheduling.h index 2f98ade2..2a2f32a0 100644 --- a/bsp_hosted/scheduling.h +++ b/bsp_hosted/scheduling.h @@ -1,9 +1,6 @@ -#ifndef _BSP_HOSTED_SCHEDULING_H_ -#define _BSP_HOSTED_SCHEDULING_H_ +#pragma once namespace scheduling { void initMission(); void initTasks(); }; // namespace scheduling - -#endif diff --git a/linux/scheduling.h b/linux/scheduling.h index ef15cd23..d33e9d1f 100644 --- a/linux/scheduling.h +++ b/linux/scheduling.h @@ -1,5 +1,4 @@ -#ifndef _LINUX_SCHEDULING_H -#define _LINUX_SCHEDULING_H +#pragma once #include @@ -8,5 +7,3 @@ void schedulingScex(TaskFactory& factory, PeriodicTaskIF*& scexDevHandler, PeriodicTaskIF*& scexReaderTask); void addMpsocSupvHandlers(PeriodicTaskIF* task); } // namespace scheduling - -#endif From 38e74e6eaf099b2d86dce16148359ae6a22734e4 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 17:24:38 +0100 Subject: [PATCH 102/176] rename ploc supv uart man --- bsp_hosted/ObjectFactory.cpp | 2 +- bsp_hosted/scheduling.cpp | 6 ++ linux/devices/ploc/PlocSupervisorHandler.cpp | 20 ++-- linux/devices/ploc/PlocSupervisorHandler.h | 4 +- linux/devices/ploc/PlocSupvUartMan.cpp | 99 ++++++++++---------- linux/devices/ploc/PlocSupvUartMan.h | 10 +- 6 files changed, 74 insertions(+), 67 deletions(-) diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index 01d6da22..c384c7ad 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -98,7 +98,7 @@ void ObjectFactory::produce(void* args) { new UartCookie(objects::PLOC_SUPERVISOR_HANDLER, plocSupvString, uart::PLOC_SUPV_BAUD, supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL); supervisorCookie->setNoFixedSizeReply(); - auto supvHelper = new PlocSupvHelper(objects::PLOC_SUPERVISOR_HELPER); + auto supvHelper = new PlocSupvUartManager(objects::PLOC_SUPERVISOR_HELPER); new PlocSupervisorHandler(objects::PLOC_SUPERVISOR_HANDLER, objects::PLOC_SUPERVISOR_HELPER, supervisorCookie, Gpio(gpioIds::ENABLE_SUPV_UART, dummyGpioIF), pcdu::PDU1_CH6_PLOC_12V, supvHelper); diff --git a/bsp_hosted/scheduling.cpp b/bsp_hosted/scheduling.cpp index 9c239eb3..d7238a80 100644 --- a/bsp_hosted/scheduling.cpp +++ b/bsp_hosted/scheduling.cpp @@ -195,6 +195,12 @@ void scheduling::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/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index f5f333fa..9e9653ed 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -20,7 +20,7 @@ using namespace returnvalue; PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie, Gpio uartIsolatorSwitch, power::Switch_t powerSwitch, - PlocSupvHelper* supvHelper) + PlocSupvUartManager* supvHelper) : DeviceHandlerBase(objectId, uartComIFid, comCookie), uartIsolatorSwitch(uartIsolatorSwitch), hkset(this), @@ -796,12 +796,12 @@ void PlocSupervisorHandler::handleEvent(EventMessage* eventMessage) { 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) { + 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) { result = this->executeAction(supv::SHUTDOWN_MPSOC, NO_COMMANDER, nullptr, 0); if (result != returnvalue::OK) { triggerEvent(SUPV_MPSOC_SHUWDOWN_BUILD_FAILED); @@ -1856,9 +1856,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 " diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 27f80ae0..a152349c 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -34,7 +34,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { public: PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie, Gpio uartIsolatorSwitch, power::Switch_t powerSwitch, - PlocSupvHelper* supvHelper); + PlocSupvUartManager* supvHelper); virtual ~PlocSupervisorHandler(); virtual ReturnValue_t initialize() override; @@ -130,7 +130,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { const power::Switch_t powerSwitch = power::NO_SWITCH; supv::TmBase tmReader; - PlocSupvHelper* supvHelper = nullptr; + PlocSupvUartManager* supvHelper = nullptr; MessageQueueIF* eventQueue = nullptr; /** Number of expected replies following the MRAM dump command */ diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 3189cb65..f17033a7 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -27,7 +27,7 @@ using namespace returnvalue; using namespace supv; -PlocSupvHelper::PlocSupvHelper(object_id_t objectId) +PlocSupvUartManager::PlocSupvUartManager(object_id_t objectId) : SystemObject(objectId), recRingBuf(4096, true), decodedRingBuf(1200 * MAX_STORED_DECODED_PACKETS, true), @@ -39,9 +39,9 @@ PlocSupvHelper::PlocSupvHelper(object_id_t objectId) ipcLock = MutexFactory::instance()->createMutex(); } -PlocSupvHelper::~PlocSupvHelper() = default; +PlocSupvUartManager::~PlocSupvUartManager() = default; -ReturnValue_t PlocSupvHelper::initializeInterface(CookieIF* cookie) { +ReturnValue_t PlocSupvUartManager::initializeInterface(CookieIF* cookie) { auto* uartCookie = dynamic_cast(cookie); if (uartCookie == nullptr) { return FAILED; @@ -80,7 +80,7 @@ ReturnValue_t PlocSupvHelper::initializeInterface(CookieIF* cookie) { return OK; } -ReturnValue_t PlocSupvHelper::initialize() { +ReturnValue_t PlocSupvUartManager::initialize() { #ifdef XIPHOS_Q7S sdcMan = SdCardManager::instance(); if (sdcMan == nullptr) { @@ -91,7 +91,7 @@ ReturnValue_t PlocSupvHelper::initialize() { return returnvalue::OK; } -ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { +ReturnValue_t PlocSupvUartManager::performOperation(uint8_t operationCode) { bool putTaskToSleep = false; while (true) { semaphore->acquire(); @@ -129,7 +129,7 @@ ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { } } -bool PlocSupvHelper::handleUartReception() { +bool PlocSupvUartManager::handleUartReception() { ReturnValue_t result = OK; ssize_t bytesRead = read(serialPort, reinterpret_cast(recBuf.data()), static_cast(recBuf.size())); @@ -160,8 +160,8 @@ bool PlocSupvHelper::handleUartReception() { return false; } -ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId, - uint32_t startAddress) { +ReturnValue_t PlocSupvUartManager::startUpdate(std::string file, uint8_t memoryId, + uint32_t startAddress) { supv::UpdateParams params; params.file = file; params.memId = memoryId; @@ -172,7 +172,7 @@ ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId, return performUpdate(params); } -ReturnValue_t PlocSupvHelper::performUpdate(const supv::UpdateParams& params) { +ReturnValue_t PlocSupvUartManager::performUpdate(const supv::UpdateParams& params) { lock->lockMutex(); InternalState current = state; lock->unlockMutex(); @@ -226,8 +226,8 @@ ReturnValue_t PlocSupvHelper::performUpdate(const supv::UpdateParams& params) { return result; } -ReturnValue_t PlocSupvHelper::performMemCheck(std::string file, uint8_t memoryId, - uint32_t startAddress) { +ReturnValue_t PlocSupvUartManager::performMemCheck(std::string file, uint8_t memoryId, + uint32_t startAddress) { lock->lockMutex(); InternalState current = state; lock->unlockMutex(); @@ -237,9 +237,9 @@ ReturnValue_t PlocSupvHelper::performMemCheck(std::string file, uint8_t memoryId return performMemCheck(file, memoryId, startAddress, getFileSize(update.file), true); } -ReturnValue_t PlocSupvHelper::performMemCheck(std::string file, uint8_t memoryId, - uint32_t startAddress, size_t sizeToCheck, - bool checkCrc) { +ReturnValue_t PlocSupvUartManager::performMemCheck(std::string file, uint8_t memoryId, + uint32_t startAddress, size_t sizeToCheck, + bool checkCrc) { { MutexGuard mg(lock); update.file = file; @@ -254,7 +254,7 @@ ReturnValue_t PlocSupvHelper::performMemCheck(std::string file, uint8_t memoryId return returnvalue::OK; } -ReturnValue_t PlocSupvHelper::initiateUpdateContinuation() { +ReturnValue_t PlocSupvUartManager::initiateUpdateContinuation() { lock->lockMutex(); InternalState current = state; lock->unlockMutex(); @@ -284,12 +284,12 @@ ReturnValue_t PlocSupvHelper::initiateUpdateContinuation() { // return returnvalue::OK; // } -void PlocSupvHelper::stop() { +void PlocSupvUartManager::stop() { MutexGuard mg(lock); state = InternalState::GO_TO_SLEEP; } -void PlocSupvHelper::executeFullCheckMemoryCommand() { +void PlocSupvUartManager::executeFullCheckMemoryCommand() { ReturnValue_t result; if (update.crcShouldBeChecked) { sif::info << "PLOC SUPV Mem Check: Calculating Image CRC" << std::endl; @@ -315,7 +315,7 @@ void PlocSupvHelper::executeFullCheckMemoryCommand() { handleCheckMemoryCommand(); } -ReturnValue_t PlocSupvHelper::executeUpdate() { +ReturnValue_t PlocSupvUartManager::executeUpdate() { ReturnValue_t result = returnvalue::OK; sif::info << "PLOC SUPV Update MPSoC: Calculating Image CRC" << std::endl; result = calcImageCrc(); @@ -342,7 +342,7 @@ ReturnValue_t PlocSupvHelper::executeUpdate() { return updateOperation(); } -ReturnValue_t PlocSupvHelper::continueUpdate() { +ReturnValue_t PlocSupvUartManager::continueUpdate() { ReturnValue_t result = prepareUpdate(); if (result != returnvalue::OK) { return result; @@ -350,7 +350,7 @@ ReturnValue_t PlocSupvHelper::continueUpdate() { return updateOperation(); } -ReturnValue_t PlocSupvHelper::updateOperation() { +ReturnValue_t PlocSupvUartManager::updateOperation() { sif::info << "PlocSupvHelper::performUpdate: Writing Update Packets" << std::endl; auto result = writeUpdatePackets(); if (result != returnvalue::OK) { @@ -360,7 +360,7 @@ ReturnValue_t PlocSupvHelper::updateOperation() { return handleCheckMemoryCommand(); } -ReturnValue_t PlocSupvHelper::writeUpdatePackets() { +ReturnValue_t PlocSupvUartManager::writeUpdatePackets() { ReturnValue_t result = returnvalue::OK; #if OBSW_DEBUG_PLOC_SUPERVISOR == 1 ProgressPrinter progressPrinter("Supervisor update", update.fullFileSize, @@ -437,7 +437,7 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { return result; } -uint32_t PlocSupvHelper::buildProgParams1(uint8_t percent, uint16_t seqCount) { +uint32_t PlocSupvUartManager::buildProgParams1(uint8_t percent, uint16_t seqCount) { return (static_cast(percent) << 24) | static_cast(seqCount); } @@ -482,7 +482,7 @@ uint32_t PlocSupvHelper::buildProgParams1(uint8_t percent, uint16_t seqCount) { // return result; // } -ReturnValue_t PlocSupvHelper::handleRemainingExeReport(ploc::SpTmReader& reader) { +ReturnValue_t PlocSupvUartManager::handleRemainingExeReport(ploc::SpTmReader& reader) { size_t remBytes = reader.getPacketDataLen() + 1; ReturnValue_t result = handleTmReception(remBytes, tmBuf.data() + ccsds::HEADER_LEN); if (result != returnvalue::OK) { @@ -495,7 +495,7 @@ ReturnValue_t PlocSupvHelper::handleRemainingExeReport(ploc::SpTmReader& reader) return result; } -ReturnValue_t PlocSupvHelper::selectMemory() { +ReturnValue_t PlocSupvUartManager::selectMemory() { ReturnValue_t result = returnvalue::OK; resetSpParams(); supv::MPSoCBootSelect packet(spParams); @@ -510,7 +510,7 @@ ReturnValue_t PlocSupvHelper::selectMemory() { return returnvalue::OK; } -ReturnValue_t PlocSupvHelper::prepareUpdate() { +ReturnValue_t PlocSupvUartManager::prepareUpdate() { ReturnValue_t result = returnvalue::OK; resetSpParams(); supv::NoPayloadPacket packet(spParams, Apid::BOOT_MAN, @@ -526,7 +526,7 @@ ReturnValue_t PlocSupvHelper::prepareUpdate() { return returnvalue::OK; } -ReturnValue_t PlocSupvHelper::eraseMemory() { +ReturnValue_t PlocSupvUartManager::eraseMemory() { ReturnValue_t result = returnvalue::OK; resetSpParams(); supv::EraseMemory eraseMemory(spParams); @@ -542,8 +542,8 @@ ReturnValue_t PlocSupvHelper::eraseMemory() { return returnvalue::OK; } -ReturnValue_t PlocSupvHelper::handlePacketTransmissionNoReply(supv::TcBase& packet, - uint32_t timeoutExecutionReport) { +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) { @@ -599,7 +599,7 @@ ReturnValue_t PlocSupvHelper::handlePacketTransmissionNoReply(supv::TcBase& pack return returnvalue::OK; } -int PlocSupvHelper::handleAckReception(supv::TcBase& tc, uint8_t serviceId, size_t packetLen) { +int PlocSupvUartManager::handleAckReception(supv::TcBase& tc, uint8_t serviceId, size_t packetLen) { if (serviceId == static_cast(supv::tm::TmtcId::ACK) or serviceId == static_cast(supv::tm::TmtcId::NAK)) { AcknowledgmentReport ackReport(tmReader); @@ -629,7 +629,8 @@ int PlocSupvHelper::handleAckReception(supv::TcBase& tc, uint8_t serviceId, size return 0; } -int PlocSupvHelper::handleExeAckReception(supv::TcBase& tc, uint8_t serviceId, size_t packetLen) { +int PlocSupvUartManager::handleExeAckReception(supv::TcBase& tc, uint8_t serviceId, + size_t packetLen) { if (serviceId == static_cast(supv::tm::TmtcId::EXEC_ACK) or serviceId == static_cast(supv::tm::TmtcId::EXEC_NAK)) { ExecutionReport exeReport(tmReader); @@ -659,7 +660,7 @@ int PlocSupvHelper::handleExeAckReception(supv::TcBase& tc, uint8_t serviceId, s return 0; } -ReturnValue_t PlocSupvHelper::checkReceivedTm() { +ReturnValue_t PlocSupvUartManager::checkReceivedTm() { ReturnValue_t result = tmReader.checkSize(); if (result != returnvalue::OK) { triggerEvent(SUPV_REPLY_SIZE_MISSMATCH, rememberApid); @@ -673,7 +674,7 @@ ReturnValue_t PlocSupvHelper::checkReceivedTm() { return result; } -ReturnValue_t PlocSupvHelper::calcImageCrc() { +ReturnValue_t PlocSupvUartManager::calcImageCrc() { ReturnValue_t result = returnvalue::OK; if (update.fullFileSize == 0) { return returnvalue::FAILED; @@ -719,7 +720,7 @@ ReturnValue_t PlocSupvHelper::calcImageCrc() { return result; } -ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { +ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand() { ReturnValue_t result = returnvalue::OK; resetSpParams(); supv::CheckMemory packet(spParams); @@ -815,7 +816,7 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { return result; } -uint32_t PlocSupvHelper::getFileSize(std::string filename) { +uint32_t PlocSupvUartManager::getFileSize(std::string filename) { std::ifstream file(filename, std::ifstream::binary); file.seekg(0, file.end); uint32_t size = file.tellg(); @@ -823,7 +824,7 @@ uint32_t PlocSupvHelper::getFileSize(std::string filename) { return size; } -ReturnValue_t PlocSupvHelper::handleEventBufferReception(ploc::SpTmReader& reader) { +ReturnValue_t PlocSupvUartManager::handleEventBufferReception(ploc::SpTmReader& reader) { ReturnValue_t result = returnvalue::OK; // TODO: Fix //#ifdef XIPHOS_Q7S @@ -879,10 +880,10 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception(ploc::SpTmReader& reade return result; } -void PlocSupvHelper::resetSpParams() { spParams.buf = cmdBuf.data(); } +void PlocSupvUartManager::resetSpParams() { spParams.buf = cmdBuf.data(); } -ReturnValue_t PlocSupvHelper::sendMessage(CookieIF* cookie, const uint8_t* sendData, - size_t sendLen) { +ReturnValue_t PlocSupvUartManager::sendMessage(CookieIF* cookie, const uint8_t* sendData, + size_t sendLen) { if (sendData == nullptr or sendLen == 0) { return FAILED; } @@ -895,13 +896,13 @@ ReturnValue_t PlocSupvHelper::sendMessage(CookieIF* cookie, const uint8_t* sendD return encodeAndSendPacket(sendData, sendLen); } -ReturnValue_t PlocSupvHelper::getSendSuccess(CookieIF* cookie) { return returnvalue::OK; } +ReturnValue_t PlocSupvUartManager::getSendSuccess(CookieIF* cookie) { return returnvalue::OK; } -ReturnValue_t PlocSupvHelper::requestReceiveMessage(CookieIF* cookie, size_t requestLen) { +ReturnValue_t PlocSupvUartManager::requestReceiveMessage(CookieIF* cookie, size_t requestLen) { return returnvalue::OK; } -ReturnValue_t PlocSupvHelper::handleRunningLongerRequest() { +ReturnValue_t PlocSupvUartManager::handleRunningLongerRequest() { ReturnValue_t result = OK; switch (request) { case Request::UPDATE: { @@ -949,7 +950,7 @@ ReturnValue_t PlocSupvHelper::handleRunningLongerRequest() { return false; } -ReturnValue_t PlocSupvHelper::encodeAndSendPacket(const uint8_t* sendData, size_t sendLen) { +ReturnValue_t PlocSupvUartManager::encodeAndSendPacket(const uint8_t* sendData, size_t sendLen) { size_t encodedLen = 0; hdlc_add_framing(sendData, sendLen, encodedSendBuf.data(), &encodedLen); size_t bytesWritten = write(serialPort, encodedSendBuf.data(), encodedLen); @@ -961,8 +962,8 @@ ReturnValue_t PlocSupvHelper::encodeAndSendPacket(const uint8_t* sendData, size_ return returnvalue::OK; } -ReturnValue_t PlocSupvHelper::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, - size_t* size) { +ReturnValue_t PlocSupvUartManager::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, + size_t* size) { MutexGuard mg(ipcLock); if (ipcQueue.empty()) { *size = 0; @@ -977,7 +978,7 @@ ReturnValue_t PlocSupvHelper::readReceivedMessage(CookieIF* cookie, uint8_t** bu return OK; } -ReturnValue_t PlocSupvHelper::tryHdlcParsing() { +ReturnValue_t PlocSupvUartManager::tryHdlcParsing() { size_t bytesRead = 0; ReturnValue_t result = parseRecRingBufForHdlc(bytesRead); if (result == returnvalue::OK) { @@ -1001,7 +1002,7 @@ ReturnValue_t PlocSupvHelper::tryHdlcParsing() { return result; } -ReturnValue_t PlocSupvHelper::parseRecRingBufForHdlc(size_t& readSize) { +ReturnValue_t PlocSupvUartManager::parseRecRingBufForHdlc(size_t& readSize) { size_t availableData = recRingBuf.getAvailableReadData(); if (availableData == 0) { return NO_PACKET_FOUND; @@ -1043,17 +1044,17 @@ ReturnValue_t PlocSupvHelper::parseRecRingBufForHdlc(size_t& readSize) { return NO_PACKET_FOUND; } -void PlocSupvHelper::pushIpcData(const uint8_t* data, size_t len) { +void PlocSupvUartManager::pushIpcData(const uint8_t* data, size_t len) { MutexGuard mg(ipcLock); ipcRingBuf.writeData(data, len); ipcQueue.insert(len); } -uint32_t PlocSupvHelper::buildApidServiceParam1(uint8_t apid, uint8_t serviceId) { +uint32_t PlocSupvUartManager::buildApidServiceParam1(uint8_t apid, uint8_t serviceId) { return (apid << 8) | serviceId; } -void PlocSupvHelper::performUartShutdown() { +void PlocSupvUartManager::performUartShutdown() { tcflush(serialPort, TCIOFLUSH); // Clear ring buffers recRingBuf.clear(); diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index 29183406..fcf49949 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -25,9 +25,9 @@ * the supervisor and the OBC. * @author J. Meier */ -class PlocSupvHelper : public DeviceCommunicationIF, - public SystemObject, - public ExecutableObjectIF { +class PlocSupvUartManager : public DeviceCommunicationIF, + public SystemObject, + public ExecutableObjectIF { public: static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_SUPV_HELPER; @@ -115,8 +115,8 @@ class PlocSupvHelper : public DeviceCommunicationIF, //! P1: First byte percent, third and fourth byte Sequence Count, P2: Bytes written static constexpr Event SUPV_UPDATE_PROGRESS = MAKE_EVENT(30, 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; From 2b4ec6d2745ffc558332f0685510ea9f057af037 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 17:40:19 +0100 Subject: [PATCH 103/176] add start method for uart man --- bsp_hosted/ObjectFactory.cpp | 6 +++--- linux/devices/ploc/PlocSupervisorHandler.cpp | 21 ++++++-------------- linux/devices/ploc/PlocSupervisorHandler.h | 4 ++-- linux/devices/ploc/PlocSupvUartMan.cpp | 11 ++++++++++ linux/devices/ploc/PlocSupvUartMan.h | 7 ++++++- 5 files changed, 28 insertions(+), 21 deletions(-) diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index c384c7ad..10c9e46d 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -95,13 +95,13 @@ void ObjectFactory::produce(void* args) { #if OBSW_ADD_PLOC_SUPERVISOR == 1 std::string plocSupvString = "/dev/ploc_supv"; auto supervisorCookie = - new UartCookie(objects::PLOC_SUPERVISOR_HANDLER, plocSupvString, uart::PLOC_SUPV_BAUD, - supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL); + 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, objects::PLOC_SUPERVISOR_HELPER, supervisorCookie, Gpio(gpioIds::ENABLE_SUPV_UART, dummyGpioIF), - pcdu::PDU1_CH6_PLOC_12V, supvHelper); + pcdu::PDU1_CH6_PLOC_12V, *supvHelper); #endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */ #endif diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 9e9653ed..f2a7c5fe 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -20,7 +20,7 @@ using namespace returnvalue; PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie, Gpio uartIsolatorSwitch, power::Switch_t powerSwitch, - PlocSupvUartManager* supvHelper) + PlocSupvUartManager& supvHelper) : DeviceHandlerBase(objectId, uartComIFid, comCookie), uartIsolatorSwitch(uartIsolatorSwitch), hkset(this), @@ -33,9 +33,6 @@ PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t u 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); @@ -52,10 +49,6 @@ ReturnValue_t PlocSupervisorHandler::initialize() { #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 = eventSubscription(); if (result != returnvalue::OK) { @@ -87,10 +80,6 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, ReturnValue_t result = returnvalue::OK; switch (actionId) { - case TERMINATE_SUPV_HELPER: { - supvHelper->stop(); - return EXECUTION_FINISHED; - } default: break; } @@ -114,7 +103,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, if (result != returnvalue::OK) { return result; } - result = supvHelper->performUpdate(params); + result = supvHelper.performUpdate(params); if (result != returnvalue::OK) { return result; } @@ -122,7 +111,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, return EXECUTION_FINISHED; } case CONTINUE_UPDATE: { - supvHelper->initiateUpdateContinuation(); + supvHelper.initiateUpdateContinuation(); plocSupvHelperExecuting = true; return EXECUTION_FINISHED; } @@ -135,7 +124,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); + supvHelper.performMemCheck(params.file, params.memId, params.startAddr); plocSupvHelperExecuting = true; return EXECUTION_FINISHED; } @@ -150,6 +139,7 @@ void PlocSupervisorHandler::doStartUp() { switch (startupState) { case StartupState::OFF: { bootTimeout.resetTimer(); + supvHelper.start(); startupState = StartupState::BOOTING; break; } @@ -177,6 +167,7 @@ void PlocSupervisorHandler::doStartUp() { void PlocSupervisorHandler::doShutDown() { setMode(_MODE_POWER_DOWN); + supvHelper.stop(); uartIsolatorSwitch.pullLow(); startupState = StartupState::OFF; } diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index a152349c..c5034c03 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -34,7 +34,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { public: PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie, Gpio uartIsolatorSwitch, power::Switch_t powerSwitch, - PlocSupvUartManager* supvHelper); + PlocSupvUartManager& supvHelper); virtual ~PlocSupervisorHandler(); virtual ReturnValue_t initialize() override; @@ -130,7 +130,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { const power::Switch_t powerSwitch = power::NO_SWITCH; supv::TmBase tmReader; - PlocSupvUartManager* supvHelper = nullptr; + PlocSupvUartManager& supvHelper; MessageQueueIF* eventQueue = nullptr; /** Number of expected replies following the MRAM dump command */ diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index f17033a7..cdf74027 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -94,6 +94,9 @@ ReturnValue_t PlocSupvUartManager::initialize() { ReturnValue_t PlocSupvUartManager::performOperation(uint8_t operationCode) { bool putTaskToSleep = false; while (true) { + lock->lockMutex(); + state = InternalState::SLEEPING; + lock->unlockMutex(); semaphore->acquire(); while (true) { putTaskToSleep = handleUartReception(); @@ -289,6 +292,14 @@ void PlocSupvUartManager::stop() { state = InternalState::GO_TO_SLEEP; } +void PlocSupvUartManager::start() { + MutexGuard mg(lock); + if (state == InternalState::SLEEPING or state == InternalState::GO_TO_SLEEP) { + return; + } + semaphore->release(); +} + void PlocSupvUartManager::executeFullCheckMemoryCommand() { ReturnValue_t result; if (update.crcShouldBeChecked) { diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index fcf49949..da8bb176 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -148,10 +148,15 @@ class PlocSupvUartManager : public DeviceCommunicationIF, // 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 stop(); + /** + * @brief Can be used to start the UART reception + */ + void start(); + static uint32_t buildProgParams1(uint8_t percent, uint16_t seqCount); static uint32_t buildApidServiceParam1(uint8_t apid, uint8_t serviceId); From c436a2abdae472cf492637341dce08d36378439d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 17:41:15 +0100 Subject: [PATCH 104/176] rename helper --- linux/devices/ploc/PlocSupervisorHandler.cpp | 12 ++++++------ linux/devices/ploc/PlocSupervisorHandler.h | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index f2a7c5fe..6ea85c6f 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -29,7 +29,7 @@ PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t u loggingReport(this), adcReport(this), powerSwitch(powerSwitch), - supvHelper(supvHelper) { + uartManager(supvHelper) { if (comCookie == nullptr) { sif::error << "PlocSupervisorHandler: Invalid com cookie" << std::endl; } @@ -103,7 +103,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, if (result != returnvalue::OK) { return result; } - result = supvHelper.performUpdate(params); + result = uartManager.performUpdate(params); if (result != returnvalue::OK) { return result; } @@ -111,7 +111,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, return EXECUTION_FINISHED; } case CONTINUE_UPDATE: { - supvHelper.initiateUpdateContinuation(); + uartManager.initiateUpdateContinuation(); plocSupvHelperExecuting = true; return EXECUTION_FINISHED; } @@ -124,7 +124,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); + uartManager.performMemCheck(params.file, params.memId, params.startAddr); plocSupvHelperExecuting = true; return EXECUTION_FINISHED; } @@ -139,7 +139,7 @@ void PlocSupervisorHandler::doStartUp() { switch (startupState) { case StartupState::OFF: { bootTimeout.resetTimer(); - supvHelper.start(); + uartManager.start(); startupState = StartupState::BOOTING; break; } @@ -167,7 +167,7 @@ void PlocSupervisorHandler::doStartUp() { void PlocSupervisorHandler::doShutDown() { setMode(_MODE_POWER_DOWN); - supvHelper.stop(); + uartManager.stop(); uartIsolatorSwitch.pullLow(); startupState = StartupState::OFF; } diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index c5034c03..dd63c9e6 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -130,7 +130,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { const power::Switch_t powerSwitch = power::NO_SWITCH; supv::TmBase tmReader; - PlocSupvUartManager& supvHelper; + PlocSupvUartManager& uartManager; MessageQueueIF* eventQueue = nullptr; /** Number of expected replies following the MRAM dump command */ From 38e0df5d12f6fd1c96bec9f98206385878243157 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 17:42:53 +0100 Subject: [PATCH 105/176] increase prio a bit --- bsp_hosted/OBSWConfig.h.in | 2 +- bsp_hosted/scheduling.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/bsp_hosted/OBSWConfig.h.in b/bsp_hosted/OBSWConfig.h.in index f234e795..9a80286d 100644 --- a/bsp_hosted/OBSWConfig.h.in +++ b/bsp_hosted/OBSWConfig.h.in @@ -15,7 +15,7 @@ #define OBSW_ENABLE_TIMERS 1 #define OBSW_ADD_STAR_TRACKER 0 -#define OBSW_ADD_PLOC_SUPERVISOR 0 +#define OBSW_ADD_PLOC_SUPERVISOR 1 #define OBSW_ADD_PLOC_MPSOC 0 #define OBSW_ADD_SUN_SENSORS 0 #define OBSW_ADD_MGT 0 diff --git a/bsp_hosted/scheduling.cpp b/bsp_hosted/scheduling.cpp index d7238a80..76a8f2e9 100644 --- a/bsp_hosted/scheduling.cpp +++ b/bsp_hosted/scheduling.cpp @@ -166,7 +166,7 @@ void scheduling::initTasks() { #if OBSW_ADD_PLOC_SUPERVISOR == 1 PeriodicTaskIF* supvHelperTask = factory->createPeriodicTask( - "PLOC_SUPV_HELPER", 10, PeriodicTaskIF::MINIMUM_STACK_SIZE, 1.0, missedDeadlineFunc); + "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); From 42c52295f72bcdd722599357965154d38ed39d39 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 17:44:47 +0100 Subject: [PATCH 106/176] re-run generators --- generators/bsp_q7s_events.csv | 61 ++++++++++--------- generators/events/translateEvents.cpp | 19 ++++-- generators/objects/translateObjects.cpp | 2 +- linux/fsfwconfig/events/translateEvents.cpp | 19 ++++-- linux/fsfwconfig/objects/translateObjects.cpp | 2 +- tmtc | 2 +- 6 files changed, 63 insertions(+), 42 deletions(-) diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index 7dace6d3..bb762004 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_SHUWDOWN_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,31 @@ 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 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/events/translateEvents.cpp b/generators/events/translateEvents.cpp index ee85e05c..1b534866 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 237 translations. * @details - * Generated on: 2022-11-14 17:10:10 + * Generated on: 2022-11-15 17:44:20 */ #include "translateEvents.h" @@ -129,9 +129,12 @@ 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"; @@ -487,12 +490,18 @@ 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_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; diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index 96a2d656..4856c347 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-15 17:44:20 */ #include "translateObjects.h" diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index ee85e05c..1b534866 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 237 translations. * @details - * Generated on: 2022-11-14 17:10:10 + * Generated on: 2022-11-15 17:44:20 */ #include "translateEvents.h" @@ -129,9 +129,12 @@ 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"; @@ -487,12 +490,18 @@ 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_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; diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index 96a2d656..4856c347 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-15 17:44:20 */ #include "translateObjects.h" diff --git a/tmtc b/tmtc index 66a1362e..a7999bdb 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 66a1362e7e977e427a66fd3176a9e7b6bc1b5998 +Subproject commit a7999bdbb1d3f490d383c3b085b9019730ec1450 From 3059e196a3d46ea225e9bb4afc67262e96cf3d38 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 17:47:24 +0100 Subject: [PATCH 107/176] update object list --- .../fsfwconfig/objects/translateObjects.cpp | 414 ++++++++++++++++-- .../fsfwconfig/objects/translateObjects.h | 2 +- 2 files changed, 381 insertions(+), 35 deletions(-) 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_ */ From a55e6a17254d41deaf294caad2358d530c893572 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 17:48:44 +0100 Subject: [PATCH 108/176] logic fix --- linux/devices/ploc/PlocSupvUartMan.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index cdf74027..047bef59 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -294,7 +294,7 @@ void PlocSupvUartManager::stop() { void PlocSupvUartManager::start() { MutexGuard mg(lock); - if (state == InternalState::SLEEPING or state == InternalState::GO_TO_SLEEP) { + if (state != InternalState::SLEEPING and state != InternalState::GO_TO_SLEEP) { return; } semaphore->release(); From 1f6f11ee88998c7c397d39d2a6aaba91faeaf2ee Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 17:51:22 +0100 Subject: [PATCH 109/176] bugfix for start method --- linux/devices/ploc/PlocSupvUartMan.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 047bef59..8b341c56 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -289,6 +289,9 @@ ReturnValue_t PlocSupvUartManager::initiateUpdateContinuation() { void PlocSupvUartManager::stop() { MutexGuard mg(lock); + if(state == InternalState::SLEEPING or state == InternalState::GO_TO_SLEEP) { + return; + } state = InternalState::GO_TO_SLEEP; } @@ -297,6 +300,7 @@ void PlocSupvUartManager::start() { if (state != InternalState::SLEEPING and state != InternalState::GO_TO_SLEEP) { return; } + state = InternalState::DEFAULT; semaphore->release(); } From 9163db6bcf6b6eb115e8ddaa91d60bb6a1afd7f9 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 15 Nov 2022 18:02:17 +0100 Subject: [PATCH 110/176] add debug statements --- linux/devices/ploc/PlocSupvUartMan.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 8b341c56..47e63da7 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -3,6 +3,8 @@ #include #include #include + +#include #include #include @@ -99,6 +101,7 @@ ReturnValue_t PlocSupvUartManager::performOperation(uint8_t operationCode) { lock->unlockMutex(); semaphore->acquire(); while (true) { + sif::debug << "SUPV UART MAN: Running.." << std::endl; putTaskToSleep = handleUartReception(); if (putTaskToSleep) { performUartShutdown(); @@ -968,6 +971,8 @@ ReturnValue_t PlocSupvUartManager::handleRunningLongerRequest() { ReturnValue_t PlocSupvUartManager::encodeAndSendPacket(const uint8_t* sendData, size_t sendLen) { size_t encodedLen = 0; hdlc_add_framing(sendData, sendLen, encodedSendBuf.data(), &encodedLen); + sif::debug << "Sending TC" << std::endl; + arrayprinter::print(encodedSendBuf.data(), encodedLen); size_t bytesWritten = write(serialPort, encodedSendBuf.data(), encodedLen); if (bytesWritten != encodedLen) { sif::warning << "ScexUartReader::sendMessage: Sending ping command to solar experiment failed" From 32005a2d3ae8252689116cdf50c8d19a1e535d13 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 16 Nov 2022 11:57:29 +0100 Subject: [PATCH 111/176] more printouts, switch on debug mode --- linux/devices/ploc/PlocSupvUartMan.cpp | 3 ++- linux/devices/ploc/PlocSupvUartMan.h | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 47e63da7..a80e23a8 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -159,6 +159,7 @@ bool PlocSupvUartManager::handleUartReception() { } 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); tryHdlcParsing(); @@ -1013,7 +1014,7 @@ ReturnValue_t PlocSupvUartManager::tryHdlcParsing() { } recRingBuf.deleteData(bytesRead); } else if (result != NO_PACKET_FOUND) { - sif::warning << "ScexUartReader::performOperation: Possible packet loss" << std::endl; + 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? diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index da8bb176..d872ff03 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -248,7 +248,7 @@ class PlocSupvUartManager : public DeviceCommunicationIF, std::array tmBuf{}; - bool debugMode = false; + bool debugMode = true; bool timestamping = true; // Remembers APID to know at which command a procedure failed From 3510cc85fcc330d1ca9c1e8047af37bdb051f0ad Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 16 Nov 2022 13:26:49 +0100 Subject: [PATCH 112/176] a lot of bugfixes --- linux/devices/ploc/PlocSupervisorHandler.cpp | 11 +++++--- linux/devices/ploc/PlocSupvUartMan.cpp | 27 ++++++++++---------- linux/devices/ploc/PlocSupvUartMan.h | 6 ++--- thirdparty/tas/hdlc.c | 7 ++--- thirdparty/tas/tas/hdlc.h | 2 +- 5 files changed, 28 insertions(+), 25 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 6ea85c6f..8f77d619 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -1,6 +1,7 @@ #include "PlocSupervisorHandler.h" #include +#include #include #include @@ -586,6 +587,8 @@ ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t r // } tmReader.setData(start, remainingSize); + sif::debug << "PlocSupervisorHandler::scanForReply: Received Packet" << std::endl; + arrayprinter::print(start, remainingSize); uint16_t apid = tmReader.getApid(); //(*(start) << 8 | *(start + 1)) & APID_MASK; switch (apid) { @@ -1915,13 +1918,13 @@ void PlocSupervisorHandler::handleBadApidServiceCombination(Event event, unsigne unsigned int serviceId) { const char* printString = ""; if (event == SUPV_UNKNOWN_TM) { - printString = "Unknown"; + printString = "PlocSupervisorHandler: Unknown"; } else if (event == SUPV_UNINIMPLEMENTED_TM) { - printString = "Unimplemented"; + printString = "PlocSupervisorHandler: Unimplemented"; } triggerEvent(event, apid, tmReader.getServiceId()); - sif::error << printString << " APID service combination 0x" << std::setw(2) << std::setfill('0') - << std::hex << apid << ", " << std::setw(2) << serviceId << std::endl; + 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) { diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index a80e23a8..4d4bee06 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -1,10 +1,9 @@ #include #include // Contains file controls like O_RDWR #include +#include #include #include - -#include #include #include @@ -293,8 +292,8 @@ ReturnValue_t PlocSupvUartManager::initiateUpdateContinuation() { void PlocSupvUartManager::stop() { MutexGuard mg(lock); - if(state == InternalState::SLEEPING or state == InternalState::GO_TO_SLEEP) { - return; + if (state == InternalState::SLEEPING or state == InternalState::GO_TO_SLEEP) { + return; } state = InternalState::GO_TO_SLEEP; } @@ -1001,16 +1000,17 @@ ReturnValue_t PlocSupvUartManager::readReceivedMessage(CookieIF* cookie, uint8_t ReturnValue_t PlocSupvUartManager::tryHdlcParsing() { size_t bytesRead = 0; - ReturnValue_t result = parseRecRingBufForHdlc(bytesRead); + 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(), bytesRead); - decodedQueue.insert(bytesRead); + decodedRingBuf.writeData(decodedBuf.data(), decodedLen); + decodedQueue.insert(decodedLen); } else { MutexGuard mg(ipcLock); - ipcRingBuf.writeData(decodedBuf.data(), bytesRead); - ipcQueue.insert(bytesRead); + ipcRingBuf.writeData(decodedBuf.data(), decodedLen); + ipcQueue.insert(decodedLen); } recRingBuf.deleteData(bytesRead); } else if (result != NO_PACKET_FOUND) { @@ -1023,7 +1023,7 @@ ReturnValue_t PlocSupvUartManager::tryHdlcParsing() { return result; } -ReturnValue_t PlocSupvUartManager::parseRecRingBufForHdlc(size_t& readSize) { +ReturnValue_t PlocSupvUartManager::parseRecRingBufForHdlc(size_t& readSize, size_t& decodedLen) { size_t availableData = recRingBuf.getAvailableReadData(); if (availableData == 0) { return NO_PACKET_FOUND; @@ -1037,7 +1037,6 @@ ReturnValue_t PlocSupvUartManager::parseRecRingBufForHdlc(size_t& readSize) { } bool startMarkerFound = false; size_t startIdx = 0; - return returnvalue::OK; for (size_t idx = 0; idx < availableData; idx++) { // handle start marker if (encodedBuf[idx] == HDLC_START_MARKER) { @@ -1052,9 +1051,9 @@ ReturnValue_t PlocSupvUartManager::parseRecRingBufForHdlc(size_t& readSize) { if (encodedBuf[idx] == HDLC_END_MARKER) { if (startMarkerFound) { // Probably a packet, so decode it - size_t decodedLen = 0; - hdlc_remove_framing(encodedBuf.data() + startIdx, idx + 1, decodedBuf.data(), &decodedLen); - readSize = decodedLen; + hdlc_remove_framing(encodedBuf.data() + startIdx, idx + 1 - startIdx, decodedBuf.data(), + &decodedLen); + readSize = idx + 1; return returnvalue::OK; } else { readSize = ++idx; diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index d872ff03..ada96bf5 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -177,8 +177,8 @@ class PlocSupvUartManager : public DeviceCommunicationIF, 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 = 0x7C; - static constexpr uint8_t HDLC_END_MARKER = 0x7E; + static constexpr uint8_t HDLC_START_MARKER = 0x7E; + static constexpr uint8_t HDLC_END_MARKER = 0x7C; struct Update { uint8_t memoryId; @@ -261,7 +261,7 @@ class PlocSupvUartManager : public DeviceCommunicationIF, void executeFullCheckMemoryCommand(); ReturnValue_t tryHdlcParsing(); - ReturnValue_t parseRecRingBufForHdlc(size_t& readSize); + ReturnValue_t parseRecRingBufForHdlc(size_t& readSize, size_t& decodedLen); ReturnValue_t executeUpdate(); ReturnValue_t continueUpdate(); ReturnValue_t updateOperation(); diff --git a/thirdparty/tas/hdlc.c b/thirdparty/tas/hdlc.c index 4734c0b9..49808c1f 100644 --- a/thirdparty/tas/hdlc.c +++ b/thirdparty/tas/hdlc.c @@ -55,15 +55,15 @@ void hdlc_add_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dle *dlen = tlen; } -void hdlc_remove_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen) +int hdlc_remove_framing(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 == 0) return; - if ((src[tlen] != 0x7E) && (src[slen-1] != 0x7C)) return; + if (slen == 0) return -1; + if ((src[tlen] != 0x7E) && (src[slen-1] != 0x7C)) return -1; for (ii = 1; ii < slen-1; ii++) { bt = *src++; @@ -75,6 +75,7 @@ void hdlc_remove_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t * dst[tlen++] = bt; } *dlen = tlen; + return 0; } diff --git a/thirdparty/tas/tas/hdlc.h b/thirdparty/tas/tas/hdlc.h index 97e69500..5599070b 100644 --- a/thirdparty/tas/tas/hdlc.h +++ b/thirdparty/tas/tas/hdlc.h @@ -28,7 +28,7 @@ extern "C" { void hdlc_add_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen); -void hdlc_remove_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen); +int hdlc_remove_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen); #ifdef __cplusplus } From 5b770a6407976b29b1da869d6e2b1cda20c23775 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 16 Nov 2022 14:42:18 +0100 Subject: [PATCH 113/176] remove HDLC framing including CRC --- linux/devices/ploc/PlocSupvUartMan.cpp | 9 +++++++-- linux/devices/ploc/PlocSupvUartMan.h | 3 +++ thirdparty/tas/hdlc.c | 12 ++++++++---- thirdparty/tas/tas/hdlc.h | 15 ++++++++++++++- 4 files changed, 32 insertions(+), 7 deletions(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 4d4bee06..19dd25e0 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -1051,9 +1051,14 @@ ReturnValue_t PlocSupvUartManager::parseRecRingBufForHdlc(size_t& readSize, size if (encodedBuf[idx] == HDLC_END_MARKER) { if (startMarkerFound) { // Probably a packet, so decode it - hdlc_remove_framing(encodedBuf.data() + startIdx, idx + 1 - startIdx, decodedBuf.data(), - &decodedLen); + int retval = hdlc_remove_framing_with_crc_check( + 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); + } return returnvalue::OK; } else { readSize = ++idx; diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index ada96bf5..58abf68b 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -114,6 +114,8 @@ class PlocSupvUartManager : public DeviceCommunicationIF, //! [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); PlocSupvUartManager(object_id_t objectId); virtual ~PlocSupvUartManager(); @@ -167,6 +169,7 @@ class PlocSupvUartManager : public DeviceCommunicationIF, 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 diff --git a/thirdparty/tas/hdlc.c b/thirdparty/tas/hdlc.c index 49808c1f..428a28da 100644 --- a/thirdparty/tas/hdlc.c +++ b/thirdparty/tas/hdlc.c @@ -55,15 +55,15 @@ void hdlc_add_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dle *dlen = tlen; } -int hdlc_remove_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen) +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 == 0) return -1; - if ((src[tlen] != 0x7E) && (src[slen-1] != 0x7C)) return -1; + if (slen < 4) return -1; + if ((src[tlen] != 0x7E) && (src[slen-1] != 0x7C)) return -2; for (ii = 1; ii < slen-1; ii++) { bt = *src++; @@ -74,7 +74,11 @@ int hdlc_remove_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *d } dst[tlen++] = bt; } - *dlen = tlen; + // calc crc16 + if(calc_crc16_buff_reflected( dst, tlen ) != 0) { + return 1; + } + *dlen = tlen - 2; return 0; } diff --git a/thirdparty/tas/tas/hdlc.h b/thirdparty/tas/tas/hdlc.h index 5599070b..c4179d11 100644 --- a/thirdparty/tas/tas/hdlc.h +++ b/thirdparty/tas/tas/hdlc.h @@ -28,7 +28,20 @@ extern "C" { void hdlc_add_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen); -int hdlc_remove_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 } From 03e007fd36d9a43b5bd4e20d596d50201d252f74 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 16 Nov 2022 14:43:22 +0100 Subject: [PATCH 114/176] afmt --- linux/devices/ploc/PlocSupvUartMan.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 19dd25e0..0833cd67 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -1059,6 +1059,9 @@ ReturnValue_t PlocSupvUartManager::parseRecRingBufForHdlc(size_t& readSize, size } else if (retval == 1) { triggerEvent(HDLC_CRC_ERROR); } + if (retval != 0) { + return HDLC_ERROR; + } return returnvalue::OK; } else { readSize = ++idx; From 3ef0b3ea6de20519d2177ec569373d5c92b9bceb Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 16 Nov 2022 15:03:10 +0100 Subject: [PATCH 115/176] TAS PLOC SUPV --- bsp_q7s/core/InitMission.cpp | 88 ++++++++++---------- bsp_q7s/core/ObjectFactory.cpp | 8 +- linux/devices/ploc/PlocSupervisorHandler.cpp | 7 +- linux/devices/ploc/PlocSupervisorHandler.h | 5 +- 4 files changed, 53 insertions(+), 55 deletions(-) diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/InitMission.cpp index bbeaded8..3b1eb357 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/InitMission.cpp @@ -1,7 +1,7 @@ #include "bsp_q7s/core/InitMission.h" #include -#include +#include #include #include @@ -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; @@ -458,7 +458,7 @@ void initmission::createPusTasks(TaskFactory& factory, "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 +466,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 +478,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 +492,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,7 +525,7 @@ 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); } @@ -542,25 +542,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/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index a416fd58..85157e66 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -628,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/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 8f77d619..feb67265 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -18,11 +18,10 @@ using namespace supv; using namespace returnvalue; -PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, - CookieIF* comCookie, Gpio uartIsolatorSwitch, - power::Switch_t powerSwitch, +PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, CookieIF* comCookie, + Gpio uartIsolatorSwitch, power::Switch_t powerSwitch, PlocSupvUartManager& supvHelper) - : DeviceHandlerBase(objectId, uartComIFid, comCookie), + : DeviceHandlerBase(objectId, supvHelper.getObjectId(), comCookie), uartIsolatorSwitch(uartIsolatorSwitch), hkset(this), bootStatusReport(this), diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index dd63c9e6..60970f33 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -32,9 +32,8 @@ using supv::ExecutionReport; */ class PlocSupervisorHandler : public DeviceHandlerBase { public: - PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie, - Gpio uartIsolatorSwitch, power::Switch_t powerSwitch, - PlocSupvUartManager& supvHelper); + PlocSupervisorHandler(object_id_t objectId, CookieIF* comCookie, Gpio uartIsolatorSwitch, + power::Switch_t powerSwitch, PlocSupvUartManager& supvHelper); virtual ~PlocSupervisorHandler(); virtual ReturnValue_t initialize() override; From eb371b30244994bbf71324be506db4ca00efb05d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 16 Nov 2022 15:05:12 +0100 Subject: [PATCH 116/176] ctor fix --- bsp_hosted/ObjectFactory.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index 10c9e46d..2fd8230f 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -99,7 +99,7 @@ void ObjectFactory::produce(void* args) { supv::MAX_PACKET_SIZE * 20, UartModes::NON_CANONICAL); supervisorCookie->setNoFixedSizeReply(); auto supvHelper = new PlocSupvUartManager(objects::PLOC_SUPERVISOR_HELPER); - new PlocSupervisorHandler(objects::PLOC_SUPERVISOR_HANDLER, 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 */ From 4e3abb92f255760121f170b3596bd084b4cefac8 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 16 Nov 2022 15:25:29 +0100 Subject: [PATCH 117/176] update events --- bsp_hosted/ObjectFactory.cpp | 6 +++--- generators/bsp_q7s_events.csv | 2 ++ generators/events/translateEvents.cpp | 10 ++++++++-- generators/objects/translateObjects.cpp | 2 +- linux/devices/ploc/PlocSupvUartMan.cpp | 6 +++--- linux/fsfwconfig/events/translateEvents.cpp | 10 ++++++++-- linux/fsfwconfig/objects/translateObjects.cpp | 2 +- tmtc | 2 +- 8 files changed, 27 insertions(+), 13 deletions(-) diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index 2fd8230f..89b83041 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -99,9 +99,9 @@ void ObjectFactory::produce(void* args) { 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); + 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 diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index bb762004..9a89eca9 100644 --- a/generators/bsp_q7s_events.csv +++ b/generators/bsp_q7s_events.csv @@ -223,6 +223,8 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 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/events/translateEvents.cpp b/generators/events/translateEvents.cpp index 1b534866..ac00745c 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 237 translations. + * @brief Auto-generated event translation file. Contains 239 translations. * @details - * Generated on: 2022-11-15 17:44:20 + * Generated on: 2022-11-16 15:25:08 */ #include "translateEvents.h" @@ -225,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"; @@ -681,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 4856c347..0890725e 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-15 17:44:20 + * Generated on: 2022-11-16 15:25:08 */ #include "translateObjects.h" diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 0833cd67..4fe9a033 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -51,8 +51,8 @@ ReturnValue_t PlocSupvUartManager::initializeInterface(CookieIF* cookie) { /* Get file descriptor */ serialPort = open(devname.c_str(), O_RDWR); if (serialPort < 0) { - sif::warning << "ScexUartReader::initializeInterface: open call failed with error [" << errno - << ", " << strerror(errno) << std::endl; + sif::warning << "PlocSupvUartManager::initializeInterface: open call failed with error [" + << errno << ", " << strerror(errno) << std::endl; return FAILED; } // Setting up UART parameters @@ -73,7 +73,7 @@ ReturnValue_t PlocSupvUartManager::initializeInterface(CookieIF* cookie) { uart::setBaudrate(tty, uartCookie->getBaudrate()); if (tcsetattr(serialPort, TCSANOW, &tty) != 0) { - sif::warning << "ScexUartReader::initializeInterface: tcsetattr call failed with error [" + sif::warning << "PlocSupvUartManager::initializeInterface: tcsetattr call failed with error [" << errno << ", " << strerror(errno) << std::endl; } // Flush received and unread data diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index 1b534866..ac00745c 100644 --- a/linux/fsfwconfig/events/translateEvents.cpp +++ b/linux/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 237 translations. + * @brief Auto-generated event translation file. Contains 239 translations. * @details - * Generated on: 2022-11-15 17:44:20 + * Generated on: 2022-11-16 15:25:08 */ #include "translateEvents.h" @@ -225,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"; @@ -681,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/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index 4856c347..0890725e 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-15 17:44:20 + * Generated on: 2022-11-16 15:25:08 */ #include "translateObjects.h" diff --git a/tmtc b/tmtc index a7999bdb..d5813e1a 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit a7999bdbb1d3f490d383c3b085b9019730ec1450 +Subproject commit d5813e1a422beae7d0cb092a885e0956e9f1ddc1 From 612a475eecf58f7cdb11be65c019988ec5115f4b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 16 Nov 2022 15:26:47 +0100 Subject: [PATCH 118/176] update event translations --- .../fsfwconfig/events/translateEvents.cpp | 480 +++++++++++++++++- .../fsfwconfig/events/translateEvents.h | 4 +- 2 files changed, 470 insertions(+), 14 deletions(-) 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_ */ From bce8c71e3887d870047363a3ce45f573280dc915 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 11:33:47 +0100 Subject: [PATCH 119/176] crc check now works --- linux/devices/ploc/PlocSupvUartMan.cpp | 61 ++++++++++++++++++++++++-- linux/devices/ploc/PlocSupvUartMan.h | 3 ++ thirdparty/tas/hdlc.c | 10 +++-- thirdparty/tas/tas/crc.h | 9 ++++ thirdparty/tas/tas/hdlc.h | 2 + 5 files changed, 79 insertions(+), 6 deletions(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 4fe9a033..ff57222d 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -970,7 +970,7 @@ ReturnValue_t PlocSupvUartManager::handleRunningLongerRequest() { ReturnValue_t PlocSupvUartManager::encodeAndSendPacket(const uint8_t* sendData, size_t sendLen) { size_t encodedLen = 0; - hdlc_add_framing(sendData, sendLen, encodedSendBuf.data(), &encodedLen); + addHdlcFraming(sendData, sendLen, encodedSendBuf.data(), &encodedLen, encodedSendBuf.size()); sif::debug << "Sending TC" << std::endl; arrayprinter::print(encodedSendBuf.data(), encodedLen); size_t bytesWritten = write(serialPort, encodedSendBuf.data(), encodedLen); @@ -1051,8 +1051,8 @@ ReturnValue_t PlocSupvUartManager::parseRecRingBufForHdlc(size_t& readSize, size if (encodedBuf[idx] == HDLC_END_MARKER) { if (startMarkerFound) { // Probably a packet, so decode it - int retval = hdlc_remove_framing_with_crc_check( - encodedBuf.data() + startIdx, idx + 1 - startIdx, decodedBuf.data(), &decodedLen); + 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); @@ -1097,3 +1097,58 @@ void PlocSupvUartManager::performUartShutdown() { } 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; + // hdlc crc16 is in little endian format + SerializeAdapter::serialize(&crc16, dst + tlen, &dummy, maxDest, SerializeIF::Endianness::LITTLE); + tlen += dummy; + + 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; + } + *dlen = tlen - 2; + return 0; +} diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index 58abf68b..bc39a477 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -15,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" @@ -259,6 +260,8 @@ class PlocSupvUartManager : public DeviceCommunicationIF, ReturnValue_t handleRunningLongerRequest(); bool 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(); diff --git a/thirdparty/tas/hdlc.c b/thirdparty/tas/hdlc.c index 428a28da..296c8988 100644 --- a/thirdparty/tas/hdlc.c +++ b/thirdparty/tas/hdlc.c @@ -14,9 +14,9 @@ #include -static void hdlc_add_byte(uint8_t ch, uint8_t *buff, uint16_t *pos) +void hdlc_add_byte(uint8_t ch, uint8_t *buff, size_t *pos) { - uint16_t templen = *pos; + size_t templen = *pos; if ((ch == 0x7E) || (ch == 0x7D) || @@ -32,7 +32,7 @@ static void hdlc_add_byte(uint8_t ch, uint8_t *buff, uint16_t *pos) void hdlc_add_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dlen) { - uint16_t tlen = 0; + size_t tlen = 0; uint16_t ii; uint16_t crc16; uint8_t bt; @@ -48,6 +48,9 @@ void hdlc_add_framing(const uint8_t *src, size_t slen, uint8_t *dst, size_t *dle } // 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); @@ -75,6 +78,7 @@ int hdlc_remove_framing_with_crc_check(const uint8_t *src, size_t slen, uint8_t dst[tlen++] = bt; } // calc crc16 + // TODO: Warning: This does not work because the CRC16 is little endian if(calc_crc16_buff_reflected( dst, tlen ) != 0) { return 1; } diff --git a/thirdparty/tas/tas/crc.h b/thirdparty/tas/tas/crc.h index a9735402..0a45653c 100644 --- a/thirdparty/tas/tas/crc.h +++ b/thirdparty/tas/tas/crc.h @@ -10,6 +10,10 @@ #ifndef TAS_D_C_CRC_H #define TAS_D_C_CRC_H +#ifdef __cplusplus +extern "C" { +#endif + #include #include @@ -104,4 +108,9 @@ void calc_crc16_byte_reflected(uint16_t *crc16, uint8_t bt); * \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 index c4179d11..b137fc4c 100644 --- a/thirdparty/tas/tas/hdlc.h +++ b/thirdparty/tas/tas/hdlc.h @@ -26,6 +26,8 @@ extern "C" { #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); /** From bb6622883789f2a52035ba84b9909cd4027fcd49 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 11:38:45 +0100 Subject: [PATCH 120/176] re-test the simpler method --- linux/devices/ploc/PlocSupvUartMan.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index ff57222d..149a553a 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -1149,6 +1149,9 @@ int PlocSupvUartManager::removeHdlcFramingWithCrcCheck(const uint8_t* src, size_ if (calcCrc != crc) { return 1; } + // if(calc_crc16_buff_reflected(dst, tlen) != 0) { + // return 1; + // } *dlen = tlen - 2; return 0; } From 53535b6023c5ff7b201959dee94fe48d8c7631da Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 11:45:09 +0100 Subject: [PATCH 121/176] fix bugs in SW --- thirdparty/tas/hdlc.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/thirdparty/tas/hdlc.c b/thirdparty/tas/hdlc.c index 296c8988..895bad7a 100644 --- a/thirdparty/tas/hdlc.c +++ b/thirdparty/tas/hdlc.c @@ -67,6 +67,7 @@ int hdlc_remove_framing_with_crc_check(const uint8_t *src, size_t slen, uint8_t *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++; @@ -74,6 +75,7 @@ int hdlc_remove_framing_with_crc_check(const uint8_t *src, size_t slen, uint8_t if (bt == 0x7D) { bt = *src++ ^ 0x20; + ii++; } dst[tlen++] = bt; } From 72f8e359bbf8c79b71cefde8f19d70f89703a24d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 13:24:39 +0100 Subject: [PATCH 122/176] CRC failure --- .../PlocSupervisorDefinitions.h | 17 ++++++++++++----- linux/devices/ploc/PlocSupervisorHandler.cpp | 2 +- linux/devices/ploc/PlocSupvUartMan.cpp | 7 ++++--- 3 files changed, 17 insertions(+), 9 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index c74e81ff..d4ec1caa 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -310,7 +310,9 @@ enum class TmtcManStatusCode : uint32_t { BAD_SP_HEADER = 0x608 }; -static const uint16_t APID_MASK = 0x3FF; +static constexpr uint16_t APID_MASK_TC = 0x200; +static constexpr uint16_t APID_MASK_TM = 0x400; +static constexpr uint16_t APID_MODULE_MASK = 0x7F; static const uint16_t SEQUENCE_COUNT_MASK = 0xFFF; static const uint8_t HK_SET_ENTRIES = 13; @@ -485,7 +487,8 @@ class TcBase : public ploc::SpTcBase { : 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, fullSpDataLenFromPayloadLen(payloadLen), seqCount) { + : ploc::SpTcBase(params, apid | APID_MASK_TC, fullSpDataLenFromPayloadLen(payloadLen), + seqCount) { setup(serviceId); } @@ -496,6 +499,8 @@ class TcBase : public ploc::SpTcBase { payloadStart[supv::PAYLOAD_OFFSET] = id; } + uint16_t getModuleApid() const { return getApid() & APID_MODULE_MASK; } + uint8_t getServiceId() const { return payloadStart[supv::PAYLOAD_OFFSET]; } static size_t fullSpDataLenFromPayloadLen(size_t payloadLen) { @@ -541,6 +546,8 @@ class TmBase : public ploc::SpTmReader { 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) { @@ -1430,7 +1437,7 @@ class VerificationReport { break; } } - } else if (statusCode < 0x200 and statusCode > 0x100) { + } else if (statusCode < 0x200 and statusCode >= 0x100) { BootManStatusCode code = static_cast(statusCode); switch (code) { case BootManStatusCode::NOTHING_TODO: { @@ -1474,7 +1481,7 @@ class VerificationReport { break; } } - } else if (statusCode < 0x300 and statusCode > 0x200) { + } else if (statusCode < 0x300 and statusCode >= 0x200) { MemManStatusCode code = static_cast(statusCode); switch (code) { case MemManStatusCode::SP_NOT_AVAILABLE: { @@ -1522,7 +1529,7 @@ class VerificationReport { break; } } - } else if (statusCode < 0x400 and statusCode > 0x300) { + } else if (statusCode < 0x400 and statusCode >= 0x300) { PowerManStatusCode code = static_cast(statusCode); switch (code) { case PowerManStatusCode::PG_LOW: { diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index feb67265..8566b5b9 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -588,7 +588,7 @@ ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t r tmReader.setData(start, remainingSize); sif::debug << "PlocSupervisorHandler::scanForReply: Received Packet" << std::endl; arrayprinter::print(start, remainingSize); - uint16_t apid = tmReader.getApid(); //(*(start) << 8 | *(start + 1)) & APID_MASK; + uint16_t apid = tmReader.getModuleApid(); switch (apid) { case (Apid::TMTC_MAN): { diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 149a553a..2ec117c5 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -583,7 +583,7 @@ ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( if (result != returnvalue::OK) { continue; } - if (tmReader.getApid() == Apid::TMTC_MAN) { + if (tmReader.getModuleApid() == Apid::TMTC_MAN) { uint8_t serviceId = tmReader.getServiceId(); int retval = 0; if (not ackReceived) { @@ -769,7 +769,7 @@ ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand() { continue; } packetWasHandled = false; - if (tmReader.getApid() == Apid::TMTC_MAN) { + if (tmReader.getModuleApid() == Apid::TMTC_MAN) { uint8_t serviceId = tmReader.getServiceId(); int retval = 0; if (not ackReceived) { @@ -790,7 +790,7 @@ ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand() { return returnvalue::FAILED; } } - } else if (tmReader.getApid() == Apid::MEM_MAN) { + } else if (tmReader.getModuleApid() == Apid::MEM_MAN) { if (ackReceived) { supv::UpdateStatusReport report(tmReader); result = report.parse(); @@ -1149,6 +1149,7 @@ int PlocSupvUartManager::removeHdlcFramingWithCrcCheck(const uint8_t* src, size_ if (calcCrc != crc) { return 1; } + // This does not work because the CRC is little endian // if(calc_crc16_buff_reflected(dst, tlen) != 0) { // return 1; // } From ffc4a3456b263a2a4ceec3545c8d06633b619e8b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 13:26:03 +0100 Subject: [PATCH 123/176] some better names --- .../devices/devicedefinitions/PlocSupervisorDefinitions.h | 2 +- linux/devices/ploc/PlocSupvUartMan.cpp | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index d4ec1caa..c3223833 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -1339,7 +1339,7 @@ class VerificationReport { /** * @brief Gets the APID of command which caused the transmission of this verification report. */ - uint8_t getRefApid() const { return refApid; } + uint8_t getRefModuleApid() const { return refApid; } uint8_t getRefServiceId() const { return refServiceId; } diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 2ec117c5..b3ac004c 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -626,14 +626,14 @@ int PlocSupvUartManager::handleAckReception(supv::TcBase& tc, uint8_t serviceId, triggerEvent(ACK_RECEPTION_FAILURE); return -1; } - if (ackReport.getRefApid() == tc.getApid() and + 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.getRefApid(), ackReport.getRefServiceId()), + buildApidServiceParam1(ackReport.getRefModuleApid(), ackReport.getRefServiceId()), ackReport.getStatusCode()); return -1; } @@ -657,14 +657,14 @@ int PlocSupvUartManager::handleExeAckReception(supv::TcBase& tc, uint8_t service triggerEvent(EXE_RECEPTION_FAILURE); return -1; } - if (exeReport.getRefApid() == tc.getApid() and + if (exeReport.getRefModuleApid() == tc.getApid() 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.getRefApid(), exeReport.getRefServiceId()), + buildApidServiceParam1(exeReport.getRefModuleApid(), exeReport.getRefServiceId()), exeReport.getStatusCode()); return -1; } From 00dd2e99a82dcd9f378fc52943c23348f124ab7b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 13:39:59 +0100 Subject: [PATCH 124/176] getting there --- .../PlocSupervisorDefinitions.h | 52 +++++++++++++++++-- linux/devices/ploc/PlocSupervisorHandler.cpp | 4 +- linux/devices/ploc/PlocSupvUartMan.cpp | 14 ++--- 3 files changed, 58 insertions(+), 12 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index c3223833..312f5c14 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -1296,7 +1296,7 @@ class VerificationReport { if (not readerBase.crcIsOk()) { return result::CRC_FAILURE; } - if (readerBase.getApid() != Apid::TMTC_MAN) { + if (readerBase.getModuleApid() != Apid::TMTC_MAN) { return result::INVALID_APID; } if (readerBase.getBufSize() < MIN_TMTC_LEN + PAYLOAD_LEN or @@ -1477,7 +1477,7 @@ class VerificationReport { break; } default: { - codeHandled = true; + codeHandled = false; break; } } @@ -1525,7 +1525,7 @@ class VerificationReport { break; } default: { - codeHandled = true; + codeHandled = false; break; } } @@ -1565,7 +1565,51 @@ class VerificationReport { break; } default: { - codeHandled = true; + 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; } } diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 8566b5b9..f7dd4fcd 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -839,7 +839,7 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) { using namespace supv; ReturnValue_t result = returnvalue::OK; - if (tmReader.checkCrc() != returnvalue::OK) { + if (not tmReader.verifyCrc()) { sif::error << "PlocSupervisorHandler::handleAckReport: CRC failure" << std::endl; nextReplyId = supv::NONE; replyRawReplyIfnotWiretapped(data, supv::SIZE_ACK_REPORT); @@ -878,7 +878,7 @@ ReturnValue_t PlocSupervisorHandler::handleExecutionReport(const uint8_t* data) using namespace supv; ReturnValue_t result = returnvalue::OK; - if (tmReader.checkCrc() != OK) { + if (not tmReader.verifyCrc()) { nextReplyId = supv::NONE; return result::CRC_FAILURE; } diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index b3ac004c..fc03cbd7 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -632,9 +632,10 @@ int PlocSupvUartManager::handleAckReception(supv::TcBase& tc, uint8_t serviceId, 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()); + triggerEvent( + SUPV_ACK_FAILURE_REPORT, + buildApidServiceParam1(ackReport.getRefModuleApid(), ackReport.getRefServiceId()), + ackReport.getStatusCode()); return -1; } // Should never happen @@ -663,9 +664,10 @@ int PlocSupvUartManager::handleExeAckReception(supv::TcBase& tc, uint8_t service 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()); + triggerEvent( + SUPV_EXE_FAILURE_REPORT, + buildApidServiceParam1(exeReport.getRefModuleApid(), exeReport.getRefServiceId()), + exeReport.getStatusCode()); return -1; } // Should never happen From 9bf6ac7a9a9f6c5b3853e1caaac506441905e1f9 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 13:48:40 +0100 Subject: [PATCH 125/176] clean up printouts a bit --- linux/devices/ploc/PlocSupervisorHandler.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index f7dd4fcd..5f4092f8 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -863,6 +863,7 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) { 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(); @@ -1927,12 +1928,11 @@ void PlocSupervisorHandler::handleBadApidServiceCombination(Event event, unsigne } 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: From cdadb024202ce4e6e20716b775b5cbd8046826f7 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 13:58:40 +0100 Subject: [PATCH 126/176] mask corrections ,set sec header flag --- .../devices/devicedefinitions/PlocSupervisorDefinitions.h | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 312f5c14..ac89c8d4 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -310,8 +310,8 @@ enum class TmtcManStatusCode : uint32_t { BAD_SP_HEADER = 0x608 }; -static constexpr uint16_t APID_MASK_TC = 0x200; -static constexpr uint16_t APID_MASK_TM = 0x400; +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; @@ -520,7 +520,8 @@ class TcBase : public ploc::SpTcBase { } std::memset(spParams.buf + ccsds::HEADER_LEN, 0, TIMESTAMP_LEN); payloadStart = spParams.buf + ccsds::HEADER_LEN + SECONDARY_HEADER_LEN; - payloadStart[supv::PAYLOAD_OFFSET] = serviceId; + spParams.buf[ccsds::HEADER_LEN + SECONDARY_HEADER_LEN - 1] = serviceId; + spParams.creator.setSecHeaderFlag(); return returnvalue::OK; } }; From 114d16224e5b910f8e3801830dd07e3b5e4374e4 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 15:22:15 +0100 Subject: [PATCH 127/176] bump fsfw --- fsfw | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fsfw b/fsfw index c5f91926..160ff799 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit c5f91926c95a8db0c7921176aa3f62cc2bebef47 +Subproject commit 160ff799ace61e24708dcf1fdeaf5fafdf23a4ca From f08709ef29e6c927f93672215b84dee6a35b19bc Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 15:24:26 +0100 Subject: [PATCH 128/176] switch off debugging spam --- linux/devices/ploc/PlocSupvUartMan.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index fc03cbd7..c423944f 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -100,7 +100,7 @@ ReturnValue_t PlocSupvUartManager::performOperation(uint8_t operationCode) { lock->unlockMutex(); semaphore->acquire(); while (true) { - sif::debug << "SUPV UART MAN: Running.." << std::endl; + // sif::debug << "SUPV UART MAN: Running.." << std::endl; putTaskToSleep = handleUartReception(); if (putTaskToSleep) { performUartShutdown(); From 9a3fd51337a2e83da268a8921aa9fad9aa370f57 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 15:48:44 +0100 Subject: [PATCH 129/176] tweak do off activity --- linux/devices/ploc/PlocSupervisorHandler.cpp | 4 ++-- linux/devices/ploc/PlocSupervisorHandler.h | 2 +- tmtc | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 5f4092f8..599ef54d 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -1230,9 +1230,9 @@ ReturnValue_t PlocSupervisorHandler::doSendReadHook() { return returnvalue::OK; } -void PlocSupervisorHandler::doOffActivity() { startupState = StartupState::OFF; } +void PlocSupervisorHandler::doOffActivity() {} -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; diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 60970f33..557639e1 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -237,7 +237,7 @@ 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 diff --git a/tmtc b/tmtc index d5813e1a..f730ff41 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit d5813e1a422beae7d0cb092a885e0956e9f1ddc1 +Subproject commit f730ff4180b02f68122f853800a6247a92ac722e From 7c821e33f04354a57e2fce64a37f6a7eaefb59cd Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 15:59:31 +0100 Subject: [PATCH 130/176] somethings wrong --- linux/devices/ploc/PlocSupvUartMan.cpp | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index c423944f..f7d15317 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -907,12 +907,12 @@ ReturnValue_t PlocSupvUartManager::sendMessage(CookieIF* cookie, const uint8_t* if (sendData == nullptr or sendLen == 0) { return FAILED; } - lock->lockMutex(); - if (state == InternalState::SLEEPING or state == InternalState::DEDICATED_REQUEST) { - lock->unlockMutex(); - return FAILED; + { + MutexGuard mg(lock); + if (state == InternalState::SLEEPING or state == InternalState::DEDICATED_REQUEST) { + return FAILED; + } } - lock->unlockMutex(); return encodeAndSendPacket(sendData, sendLen); } @@ -977,8 +977,9 @@ ReturnValue_t PlocSupvUartManager::encodeAndSendPacket(const uint8_t* sendData, arrayprinter::print(encodedSendBuf.data(), encodedLen); size_t bytesWritten = write(serialPort, encodedSendBuf.data(), encodedLen); if (bytesWritten != encodedLen) { - sif::warning << "ScexUartReader::sendMessage: Sending ping command to solar experiment failed" - << std::endl; + sif::warning + << "PlocSupvUartManager::sendMessage: Sending ping command to solar experiment failed" + << std::endl; return FAILED; } return returnvalue::OK; From 3ab27f63f2dbc24cfd218a286d4efd89f24d28ef Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 16:20:13 +0100 Subject: [PATCH 131/176] fix scheduling order --- linux/scheduling.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/linux/scheduling.cpp b/linux/scheduling.cpp index 9a4c1a93..1300266f 100644 --- a/linux/scheduling.cpp +++ b/linux/scheduling.cpp @@ -50,17 +50,17 @@ 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); #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); #endif } From ae11f73e247a8efb2b1e1aada365ae172f2e3831 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 16:43:54 +0100 Subject: [PATCH 132/176] disable debug mode --- linux/devices/ploc/PlocSupvUartMan.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index bc39a477..9f6d4fe1 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -252,7 +252,7 @@ class PlocSupvUartManager : public DeviceCommunicationIF, std::array tmBuf{}; - bool debugMode = true; + bool debugMode = false; bool timestamping = true; // Remembers APID to know at which command a procedure failed From 2c00119b47e15dc7fa2d8cc9651d04f16dc0a767 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 17:28:41 +0100 Subject: [PATCH 133/176] set SP max size --- linux/devices/ploc/PlocSupvUartMan.cpp | 1 + tmtc | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index f7d15317..da9d4b3d 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -34,6 +34,7 @@ PlocSupvUartManager::PlocSupvUartManager(object_id_t objectId) 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(); diff --git a/tmtc b/tmtc index f730ff41..066adee1 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit f730ff4180b02f68122f853800a6247a92ac722e +Subproject commit 066adee13a980f0a297ab401a10abc157a7d921d From 0857a480e517367897d7a7df446b1b1fc9efc431 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 17:39:16 +0100 Subject: [PATCH 134/176] zero init some values --- linux/devices/ploc/PlocSupvUartMan.h | 6 +++--- tmtc | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index 9f6d4fe1..ce24e721 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -190,10 +190,10 @@ class PlocSupvUartManager : public DeviceCommunicationIF, // 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; diff --git a/tmtc b/tmtc index 066adee1..9cd4846d 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 066adee13a980f0a297ab401a10abc157a7d921d +Subproject commit 9cd4846d396373325fc5e03a367fed236dfc16d7 From c248cdb876c7916619864de366accec534be4776 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 17 Nov 2022 17:46:06 +0100 Subject: [PATCH 135/176] fix for error handling longer request --- linux/devices/ploc/PlocSupvUartMan.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index da9d4b3d..ab4aea5e 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -117,10 +117,9 @@ ReturnValue_t PlocSupvUartManager::performOperation(uint8_t operationCode) { break; } case InternalState::DEDICATED_REQUEST: { - if (handleRunningLongerRequest() == REQUEST_DONE) { - MutexGuard mg(lock); - state = InternalState::DEFAULT; - } + handleRunningLongerRequest(); + MutexGuard mg(lock); + state = InternalState::DEFAULT; break; } case InternalState::DEFAULT: { From 02eff4a26f0c1cdf5a530b1ebb1f02269589577d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 18 Nov 2022 14:18:45 +0100 Subject: [PATCH 136/176] some more bugfixes --- linux/devices/ploc/PlocSupervisorHandler.cpp | 66 +++++++++++--------- linux/devices/ploc/PlocSupvUartMan.cpp | 1 - thirdparty/tas/hdlc.c | 3 +- 3 files changed, 36 insertions(+), 34 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 599ef54d..e596d768 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -977,7 +977,7 @@ 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 == result::CRC_FAILURE) { sif::error << "PlocSupervisorHandler::handleBootStatusReport: Boot status report has invalid" @@ -986,28 +986,31 @@ ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data) return result; } - uint16_t offset = supv::PAYLOAD_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); @@ -1043,7 +1046,7 @@ 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 == result::CRC_FAILURE) { sif::error << "PlocSupervisorHandler::handleLatchupStatusReport: Latchup status report has " @@ -1051,38 +1054,39 @@ ReturnValue_t PlocSupervisorHandler::handleLatchupStatusReport(const uint8_t* da return result; } - uint16_t offset = supv::PAYLOAD_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; diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index ab4aea5e..8938b5d3 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -1152,7 +1152,6 @@ int PlocSupvUartManager::removeHdlcFramingWithCrcCheck(const uint8_t* src, size_ if (calcCrc != crc) { return 1; } - // This does not work because the CRC is little endian // if(calc_crc16_buff_reflected(dst, tlen) != 0) { // return 1; // } diff --git a/thirdparty/tas/hdlc.c b/thirdparty/tas/hdlc.c index 895bad7a..92f9817f 100644 --- a/thirdparty/tas/hdlc.c +++ b/thirdparty/tas/hdlc.c @@ -80,8 +80,7 @@ int hdlc_remove_framing_with_crc_check(const uint8_t *src, size_t slen, uint8_t dst[tlen++] = bt; } // calc crc16 - // TODO: Warning: This does not work because the CRC16 is little endian - if(calc_crc16_buff_reflected( dst, tlen ) != 0) { + if(calc_crc16_buff_reflected( dst, tlen ) != 0x0f47) { return 1; } *dlen = tlen - 2; From 2a00f5af47d4c3f71ba3b0986d9fc82d413fd1a1 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 18 Nov 2022 14:20:57 +0100 Subject: [PATCH 137/176] bump deps --- fsfw | 2 +- tmtc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/fsfw b/fsfw index c5f91926..160ff799 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit c5f91926c95a8db0c7921176aa3f62cc2bebef47 +Subproject commit 160ff799ace61e24708dcf1fdeaf5fafdf23a4ca diff --git a/tmtc b/tmtc index 66a1362e..9cd4846d 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 66a1362e7e977e427a66fd3176a9e7b6bc1b5998 +Subproject commit 9cd4846d396373325fc5e03a367fed236dfc16d7 From 2bbe98a403957f627ea340aa1424d47547a2aeaa Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 18 Nov 2022 14:22:00 +0100 Subject: [PATCH 138/176] bump version and changelog --- CHANGELOG.md | 2 ++ CMakeLists.txt | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index acef9e92..7016c40f 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -10,6 +10,8 @@ list yields a list of all related PRs for each release. # [unreleased] +# [v1.16.0] 18.11.2022 + - It is now possible to compile Linux components for the hosted build conditionally PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/322 - ACS Subsystem. PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/231 diff --git a/CMakeLists.txt b/CMakeLists.txt index 97b7601c..64716301 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 15) +set(OBSW_VERSION_MINOR_IF_GIT_FAILS 16) set(OBSW_VERSION_REVISION_IF_GIT_FAILS 0) # set(CMAKE_VERBOSE TRUE) From 28c662e6a7075c798223a53b305a78deb09ab675 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 18 Nov 2022 14:26:40 +0100 Subject: [PATCH 139/176] update changelog --- CHANGELOG.md | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 7016c40f..6dd1f9da 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -10,6 +10,11 @@ list yields a list of all related PRs for each release. # [unreleased] +## Added + +- PLOC Supervisor Update: Update SW to use newest PLOC SUPV version by TAS + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/316 + # [v1.16.0] 18.11.2022 - It is now possible to compile Linux components for the hosted build conditionally From f545928adcbf2a93634059260e5bd47a2a1cf863 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 18 Nov 2022 16:13:55 +0100 Subject: [PATCH 140/176] some bugfixes --- linux/devices/ploc/PlocSupervisorHandler.cpp | 33 +++++++------------- linux/devices/ploc/PlocSupvUartMan.cpp | 11 ++++--- 2 files changed, 19 insertions(+), 25 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index e596d768..3293c652 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -136,28 +136,19 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, void PlocSupervisorHandler::doStartUp() { if (setTimeDuringStartup) { - switch (startupState) { - case StartupState::OFF: { - bootTimeout.resetTimer(); - uartManager.start(); - startupState = StartupState::BOOTING; - break; + if (startupState == StartupState::OFF) { + bootTimeout.resetTimer(); + uartManager.start(); + startupState = StartupState::BOOTING; + } + if (startupState == StartupState::BOOTING) { + if (bootTimeout.hasTimedOut()) { + uartIsolatorSwitch.pullHigh(); + 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(); diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 8938b5d3..8bc2019d 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -571,9 +571,9 @@ ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( bool ackReceived = false; bool packetWasHandled = false; while (true) { - while (result != NO_PACKET_FOUND) { + do { result = tryHdlcParsing(); - } + } while (result != NO_PACKET_FOUND); if (not decodedQueue.empty()) { size_t packetLen = 0; decodedQueue.retrieve(&packetLen); @@ -589,6 +589,7 @@ ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( if (not ackReceived) { retval = handleAckReception(packet, serviceId, packetLen); if (retval == 1) { + sif::debug << "ACK received" << std::endl; ackReceived = true; packetWasHandled = true; } else if (retval == -1) { @@ -597,6 +598,7 @@ ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( } else { retval = handleExeAckReception(packet, serviceId, packetLen); if (retval == 1) { + sif::debug << "EXE ACK received" << std::endl; break; } else if (retval == -1) { return returnvalue::FAILED; @@ -758,9 +760,10 @@ ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand() { bool packetWasHandled = false; bool exeReceived = false; while (true) { - while (result != NO_PACKET_FOUND) { + do { result = tryHdlcParsing(); - } + + } while (result != NO_PACKET_FOUND); if (not decodedQueue.empty()) { size_t packetLen = 0; decodedQueue.retrieve(&packetLen); From 98fcf06e31c66f5c6ce482394283d659d20912db Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 18 Nov 2022 17:25:52 +0100 Subject: [PATCH 141/176] various improvements and bugfixes --- .../PlocSupervisorDefinitions.h | 2 +- linux/devices/ploc/PlocSupervisorHandler.cpp | 2 +- linux/devices/ploc/PlocSupvUartMan.cpp | 67 ++++++++----------- linux/devices/ploc/PlocSupvUartMan.h | 8 +-- linux/scheduling.cpp | 4 ++ mission/devices/devicedefinitions/SpBase.h | 2 + 6 files changed, 39 insertions(+), 46 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index ac89c8d4..18e92ccb 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -501,7 +501,7 @@ class TcBase : public ploc::SpTcBase { uint16_t getModuleApid() const { return getApid() & APID_MODULE_MASK; } - uint8_t getServiceId() const { return payloadStart[supv::PAYLOAD_OFFSET]; } + uint8_t getServiceId() const { return getPacketData()[TIMESTAMP_LEN]; } static size_t fullSpDataLenFromPayloadLen(size_t payloadLen) { return SECONDARY_HEADER_LEN + payloadLen + CRC_LEN; diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 3293c652..bd027e37 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -138,12 +138,12 @@ void PlocSupervisorHandler::doStartUp() { if (setTimeDuringStartup) { if (startupState == StartupState::OFF) { bootTimeout.resetTimer(); - uartManager.start(); startupState = StartupState::BOOTING; } if (startupState == StartupState::BOOTING) { if (bootTimeout.hasTimedOut()) { uartIsolatorSwitch.pullHigh(); + uartManager.start(); startupState = StartupState::SET_TIME; } } diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 8bc2019d..0db0feef 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -101,12 +101,11 @@ ReturnValue_t PlocSupvUartManager::performOperation(uint8_t operationCode) { lock->unlockMutex(); semaphore->acquire(); while (true) { - // sif::debug << "SUPV UART MAN: Running.." << std::endl; - putTaskToSleep = handleUartReception(); if (putTaskToSleep) { performUartShutdown(); break; } + handleUartReception(); lock->lockMutex(); InternalState currentState = state; lock->unlockMutex(); @@ -126,44 +125,39 @@ ReturnValue_t PlocSupvUartManager::performOperation(uint8_t operationCode) { break; } } - if (putTaskToSleep) { - performUartShutdown(); - break; - } } } } -bool PlocSupvUartManager::handleUartReception() { +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) { - { - MutexGuard mg(lock); - if (state == InternalState::GO_TO_SLEEP) { - return true; - } - } 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 true; + 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); - tryHdlcParsing(); + status = tryHdlcParsing(); } - return false; + return status; } ReturnValue_t PlocSupvUartManager::startUpdate(std::string file, uint8_t memoryId, @@ -571,23 +565,20 @@ ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( bool ackReceived = false; bool packetWasHandled = false; while (true) { - do { - result = tryHdlcParsing(); - } while (result != NO_PACKET_FOUND); + handleUartReception(); if (not decodedQueue.empty()) { size_t packetLen = 0; decodedQueue.retrieve(&packetLen); - decodedRingBuf.readData(decodedBuf.data(), 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) { - uint8_t serviceId = tmReader.getServiceId(); int retval = 0; if (not ackReceived) { - retval = handleAckReception(packet, serviceId, packetLen); + retval = handleAckReception(packet, packetLen); if (retval == 1) { sif::debug << "ACK received" << std::endl; ackReceived = true; @@ -596,7 +587,7 @@ ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( return returnvalue::FAILED; } } else { - retval = handleExeAckReception(packet, serviceId, packetLen); + retval = handleExeAckReception(packet, packetLen); if (retval == 1) { sif::debug << "EXE ACK received" << std::endl; break; @@ -619,7 +610,8 @@ ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( return returnvalue::OK; } -int PlocSupvUartManager::handleAckReception(supv::TcBase& tc, uint8_t serviceId, size_t packetLen) { +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); @@ -650,8 +642,8 @@ int PlocSupvUartManager::handleAckReception(supv::TcBase& tc, uint8_t serviceId, return 0; } -int PlocSupvUartManager::handleExeAckReception(supv::TcBase& tc, uint8_t serviceId, - size_t packetLen) { +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); @@ -660,7 +652,7 @@ int PlocSupvUartManager::handleExeAckReception(supv::TcBase& tc, uint8_t service triggerEvent(EXE_RECEPTION_FAILURE); return -1; } - if (exeReport.getRefModuleApid() == tc.getApid() and + if (exeReport.getRefModuleApid() == tc.getModuleApid() and exeReport.getRefServiceId() == tc.getServiceId()) { if (serviceId == static_cast(supv::tm::TmtcId::EXEC_ACK)) { return 1; @@ -688,8 +680,7 @@ ReturnValue_t PlocSupvUartManager::checkReceivedTm() { triggerEvent(SUPV_REPLY_SIZE_MISSMATCH, rememberApid); return result; } - result = tmReader.checkCrc(); - if (result != returnvalue::OK) { + if (not tmReader.verifyCrc()) { triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); return result; } @@ -745,12 +736,12 @@ ReturnValue_t PlocSupvUartManager::calcImageCrc() { ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand() { ReturnValue_t result = returnvalue::OK; resetSpParams(); - supv::CheckMemory packet(spParams); - result = packet.buildPacket(update.memoryId, update.startAddress, update.fullFileSize); + supv::CheckMemory tcPacket(spParams); + result = tcPacket.buildPacket(update.memoryId, update.startAddress, update.fullFileSize); if (result != returnvalue::OK) { return result; } - result = encodeAndSendPacket(packet.getFullPacket(), packet.getFullPacketLen()); + result = encodeAndSendPacket(tcPacket.getFullPacket(), tcPacket.getFullPacketLen()); if (result != returnvalue::OK) { return result; } @@ -760,14 +751,11 @@ ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand() { bool packetWasHandled = false; bool exeReceived = false; while (true) { - do { - result = tryHdlcParsing(); - - } while (result != NO_PACKET_FOUND); + handleUartReception(); if (not decodedQueue.empty()) { size_t packetLen = 0; decodedQueue.retrieve(&packetLen); - decodedRingBuf.readData(decodedBuf.data(), packetLen); + decodedRingBuf.readData(decodedBuf.data(), packetLen, true); tmReader.setData(decodedBuf.data(), packetLen); result = checkReceivedTm(); if (result != returnvalue::OK) { @@ -775,10 +763,9 @@ ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand() { } packetWasHandled = false; if (tmReader.getModuleApid() == Apid::TMTC_MAN) { - uint8_t serviceId = tmReader.getServiceId(); int retval = 0; if (not ackReceived) { - retval = handleAckReception(packet, serviceId, packetLen); + retval = handleAckReception(tcPacket, packetLen); if (retval == 1) { packetWasHandled = true; ackReceived = true; @@ -786,7 +773,7 @@ ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand() { return returnvalue::FAILED; } } else { - retval = handleExeAckReception(packet, serviceId, packetLen); + retval = handleExeAckReception(tcPacket, packetLen); if (retval == 1) { packetWasHandled = true; exeReceived = true; diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index ce24e721..9d9e3738 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -252,14 +252,14 @@ class PlocSupvUartManager : public DeviceCommunicationIF, std::array tmBuf{}; - bool debugMode = false; + bool debugMode = true; bool timestamping = true; // Remembers APID to know at which command a procedure failed uint16_t rememberApid = 0; ReturnValue_t handleRunningLongerRequest(); - bool handleUartReception(); + 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); @@ -275,8 +275,8 @@ class PlocSupvUartManager : public DeviceCommunicationIF, // ReturnValue_t performEventBufferRequest(); ReturnValue_t handlePacketTransmissionNoReply(supv::TcBase& packet, uint32_t timeoutExecutionReport = 60000); - int handleAckReception(supv::TcBase& tc, uint8_t serviceId, size_t packetLen); - int handleExeAckReception(supv::TcBase& tc, uint8_t serviceId, size_t packetLen); + 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 diff --git a/linux/scheduling.cpp b/linux/scheduling.cpp index 1300266f..75706185 100644 --- a/linux/scheduling.cpp +++ b/linux/scheduling.cpp @@ -54,6 +54,8 @@ void scheduling::addMpsocSupvHandlers(PeriodicTaskIF* plTask) { 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 @@ -62,5 +64,7 @@ void scheduling::addMpsocSupvHandlers(PeriodicTaskIF* plTask) { 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/mission/devices/devicedefinitions/SpBase.h b/mission/devices/devicedefinitions/SpBase.h index 22c138b5..11d67a59 100644 --- a/mission/devices/devicedefinitions/SpBase.h +++ b/mission/devices/devicedefinitions/SpBase.h @@ -46,6 +46,8 @@ class SpTcBase { 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(); } From 3eed1508fda415db816f89140af6629c697ff1fd Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 21 Nov 2022 13:37:05 +0100 Subject: [PATCH 142/176] bump tmtc and scex baud --- common/config/devConf.h | 2 +- tmtc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/common/config/devConf.h b/common/config/devConf.h index 5f5a5bef..931d1ad1 100644 --- a/common/config/devConf.h +++ b/common/config/devConf.h @@ -57,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/tmtc b/tmtc index 9cd4846d..f5766ea4 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 9cd4846d396373325fc5e03a367fed236dfc16d7 +Subproject commit f5766ea419ff2213468dab7e19a81075aefd1ad9 From c1e92605d40ceace834e921d1d1582e753fe7749 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 21 Nov 2022 13:38:33 +0100 Subject: [PATCH 143/176] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 9cd4846d..f5766ea4 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 9cd4846d396373325fc5e03a367fed236dfc16d7 +Subproject commit f5766ea419ff2213468dab7e19a81075aefd1ad9 From 0a5b79b8cd68da29502900f71a8a741b6ee02db8 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 21 Nov 2022 14:01:31 +0100 Subject: [PATCH 144/176] extend power switch handling --- bsp_q7s/em/emObjectFactory.cpp | 16 ++++++++++++---- dummies/helpers.cpp | 4 +++- dummies/helpers.h | 4 +++- 3 files changed, 18 insertions(+), 6 deletions(-) diff --git a/bsp_q7s/em/emObjectFactory.cpp b/bsp_q7s/em/emObjectFactory.cpp index aba884f1..825f7c03 100644 --- a/bsp_q7s/em/emObjectFactory.cpp +++ b/bsp_q7s/em/emObjectFactory.cpp @@ -38,13 +38,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); 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 From 697e27f876827b8d8c3ad9f8b4af0bc3eaae13f3 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 21 Nov 2022 14:16:21 +0100 Subject: [PATCH 145/176] scex working --- bsp_q7s/em/emObjectFactory.cpp | 5 +++-- linux/scheduling.cpp | 11 +++++++++++ 2 files changed, 14 insertions(+), 2 deletions(-) diff --git a/bsp_q7s/em/emObjectFactory.cpp b/bsp_q7s/em/emObjectFactory.cpp index 825f7c03..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" @@ -103,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/linux/scheduling.cpp b/linux/scheduling.cpp index 1300266f..c159ccc9 100644 --- a/linux/scheduling.cpp +++ b/linux/scheduling.cpp @@ -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( From 4dfd97a3001f370197dfd917a6e7e8a6dc103c40 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 21 Nov 2022 14:17:23 +0100 Subject: [PATCH 146/176] add PCDU for EM permanently --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 21ba92cf..765f1fc9 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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} From 9953a49b09ab34d1e75ba1a4ff03ca0b570a0ac6 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 21 Nov 2022 17:55:56 +0100 Subject: [PATCH 147/176] minor improvements for PLOC SUPV update --- linux/devices/ploc/PlocSupvUartMan.cpp | 12 ++++++------ linux/devices/ploc/PlocSupvUartMan.h | 2 +- tmtc | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 0db0feef..ee91554e 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -314,17 +314,17 @@ void PlocSupvUartManager::executeFullCheckMemoryCommand() { sif::info << "PLOC SUPV Mem Check: Selecting Memory" << std::endl; result = selectMemory(); if (result != returnvalue::OK) { - triggerEvent(SUPV_MEM_CHECK_FAIL, result); + 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); + triggerEvent(SUPV_MEM_CHECK_FAIL, result, 2); return; } sif::info << "PLOC SUPV Mem Check: Memory Check" << std::endl; - handleCheckMemoryCommand(); + handleCheckMemoryCommand(3); } ReturnValue_t PlocSupvUartManager::executeUpdate() { @@ -369,7 +369,7 @@ ReturnValue_t PlocSupvUartManager::updateOperation() { return result; } sif::info << "PlocSupvHelper::performUpdate: Memory Check" << std::endl; - return handleCheckMemoryCommand(); + return handleCheckMemoryCommand(0); } ReturnValue_t PlocSupvUartManager::writeUpdatePackets() { @@ -733,7 +733,7 @@ ReturnValue_t PlocSupvUartManager::calcImageCrc() { return result; } -ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand() { +ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand(uint8_t failStep) { ReturnValue_t result = returnvalue::OK; resetSpParams(); supv::CheckMemory tcPacket(spParams); @@ -803,7 +803,7 @@ ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand() { << 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); + triggerEvent(SUPV_MEM_CHECK_FAIL, result, failStep); } } } diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index 9d9e3738..0d191b7e 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -298,7 +298,7 @@ class PlocSupvUartManager : public DeviceCommunicationIF, // 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 diff --git a/tmtc b/tmtc index f5766ea4..ac2b9cb7 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit f5766ea419ff2213468dab7e19a81075aefd1ad9 +Subproject commit ac2b9cb712405ee07b9de1950fd6c923a6f184b5 From cc79ffc57bec8fbdad4b22aed3dbeec86de869f3 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 21 Nov 2022 18:32:23 +0100 Subject: [PATCH 148/176] some remaining bugfixes --- .../PlocSupervisorDefinitions.h | 7 +--- linux/devices/ploc/PlocSupervisorHandler.cpp | 37 +++++++++---------- linux/devices/ploc/PlocSupervisorHandler.h | 8 ++-- linux/devices/ploc/PlocSupvUartMan.cpp | 5 +++ linux/devices/ploc/PlocSupvUartMan.h | 3 +- tmtc | 2 +- 6 files changed, 30 insertions(+), 32 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 18e92ccb..8c638c83 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -1681,7 +1681,7 @@ class UpdateStatusReport { if (not tmReader.crcIsOk()) { return result::CRC_FAILURE; } - if (tmReader.getApid() != Apid::MEM_MAN) { + if (tmReader.getModuleApid() != Apid::MEM_MAN) { return result::INVALID_APID; } if (tmReader.getBufSize() < MIN_TMTC_LEN + PAYLOAD_LEN or @@ -1690,10 +1690,7 @@ class UpdateStatusReport { << std::endl; return result::BUF_TOO_SMALL; } - size_t remLen = PAYLOAD_LEN; - if (remLen < PAYLOAD_LEN) { - return result::INVALID_REPLY_LENGTH; - } + 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); diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index bd027e37..3a8565eb 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -2,6 +2,7 @@ #include #include +#include #include #include @@ -84,7 +85,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, break; } - if (plocSupvHelperExecuting) { + if (uartManager.longerRequestActive()) { return result::SUPV_HELPER_EXECUTING; } @@ -98,6 +99,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, if (size > config::MAX_PATH_SIZE + config::MAX_FILENAME_SIZE) { return result::FILENAME_TOO_LONG; } + shutdownCmdSent = false; UpdateParams params; result = extractUpdateCommand(data, size, params); if (result != returnvalue::OK) { @@ -107,15 +109,15 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, if (result != returnvalue::OK) { return result; } - plocSupvHelperExecuting = true; return EXECUTION_FINISHED; } case CONTINUE_UPDATE: { + shutdownCmdSent = false; uartManager.initiateUpdateContinuation(); - plocSupvHelperExecuting = true; return EXECUTION_FINISHED; } case MEMORY_CHECK_WITH_FILE: { + shutdownCmdSent = false; UpdateParams params; ReturnValue_t result = extractBaseParams(&data, size, params); if (result != returnvalue::OK) { @@ -125,7 +127,6 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, return HasFileSystemIF::FILE_DOES_NOT_EXIST; } uartManager.performMemCheck(params.file, params.memId, params.startAddr); - plocSupvHelperExecuting = true; return EXECUTION_FINISHED; } default: @@ -777,7 +778,6 @@ 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 == PlocSupvUartManager::SUPV_UPDATE_FAILED || @@ -786,13 +786,18 @@ void PlocSupervisorHandler::handleEvent(EventMessage* eventMessage) { event == PlocSupvUartManager::SUPV_CONTINUE_UPDATE_SUCCESSFUL || event == PlocSupvUartManager::SUPV_MEM_CHECK_FAIL || event == PlocSupvUartManager::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; + // 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; @@ -1217,14 +1222,6 @@ 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::handleDeviceTm(const uint8_t* data, size_t dataSize, diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 557639e1..4ffe4166 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -59,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: @@ -81,7 +81,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { //! [EXPORT] : [COMMENT] Supervisor helper currently executing a command 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(8, 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; @@ -119,6 +119,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { SerialComIF* uartComIf = nullptr; LinuxLibgpioIF* gpioComIF = nullptr; Gpio uartIsolatorSwitch; + bool shutdownCmdSent = false; supv::HkSet hkset; supv::BootStatusReport bootStatusReport; @@ -151,9 +152,6 @@ class PlocSupervisorHandler : public DeviceHandlerBase { 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 diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index ee91554e..6d938efe 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -1148,3 +1148,8 @@ int PlocSupvUartManager::removeHdlcFramingWithCrcCheck(const uint8_t* src, size_ *dlen = tlen - 2; return 0; } + +bool PlocSupvUartManager::longerRequestActive() const { + MutexGuard mg(lock); + return state == InternalState::DEDICATED_REQUEST; +} diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index 0d191b7e..d36a9cd4 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -159,6 +159,7 @@ class PlocSupvUartManager : public DeviceCommunicationIF, * @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); @@ -252,7 +253,7 @@ class PlocSupvUartManager : public DeviceCommunicationIF, std::array tmBuf{}; - bool debugMode = true; + bool debugMode = false; bool timestamping = true; // Remembers APID to know at which command a procedure failed diff --git a/tmtc b/tmtc index ac2b9cb7..70a1d492 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit ac2b9cb712405ee07b9de1950fd6c923a6f184b5 +Subproject commit 70a1d49246b5bd5297c22d336e9dd8f58f019f90 From 1b92aa03f32cf366196cc7642ba63e8b83a308b6 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 24 Nov 2022 11:22:55 +0100 Subject: [PATCH 149/176] create dummy switcher --- bsp_hosted/ObjectFactory.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index 89b83041..6db37e93 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -1,5 +1,6 @@ #include "ObjectFactory.h" +#include #include #include #include @@ -79,6 +80,7 @@ void ObjectFactory::produce(void* args) { 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); @@ -106,7 +108,7 @@ void ObjectFactory::produce(void* args) { #endif dummy::DummyCfg cfg; - dummy::createDummies(cfg); + dummy::createDummies(cfg, *dummySwitcher); new ThermalController(objects::THERMAL_CONTROLLER); new TestTask(objects::TEST_TASK); } From cf80ab01fdcbdd23ff9f27ad188c42f63c2a098f Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 24 Nov 2022 11:22:55 +0100 Subject: [PATCH 150/176] create dummy switcher --- bsp_hosted/ObjectFactory.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index 89b83041..6db37e93 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -1,5 +1,6 @@ #include "ObjectFactory.h" +#include #include #include #include @@ -79,6 +80,7 @@ void ObjectFactory::produce(void* args) { 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); @@ -106,7 +108,7 @@ void ObjectFactory::produce(void* args) { #endif dummy::DummyCfg cfg; - dummy::createDummies(cfg); + dummy::createDummies(cfg, *dummySwitcher); new ThermalController(objects::THERMAL_CONTROLLER); new TestTask(objects::TEST_TASK); } From 63a8f31a45298eadc2c346480373a81387154541 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 24 Nov 2022 11:23:21 +0100 Subject: [PATCH 151/176] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index f5766ea4..70a1d492 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit f5766ea419ff2213468dab7e19a81075aefd1ad9 +Subproject commit 70a1d49246b5bd5297c22d336e9dd8f58f019f90 From c7b90fb8e0d0a6bf1e2a20e36aee4e0e7882fbcb Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 24 Nov 2022 11:58:41 +0100 Subject: [PATCH 152/176] something hangs up --- linux/devices/ploc/PlocSupervisorHandler.cpp | 4 +-- linux/devices/ploc/PlocSupvUartMan.cpp | 37 ++++++-------------- linux/devices/ploc/PlocSupvUartMan.h | 4 +-- tmtc | 2 +- 4 files changed, 15 insertions(+), 32 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 3a8565eb..b022f119 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -578,8 +578,8 @@ ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t r // } tmReader.setData(start, remainingSize); - sif::debug << "PlocSupervisorHandler::scanForReply: Received Packet" << std::endl; - arrayprinter::print(start, remainingSize); + // sif::debug << "PlocSupervisorHandler::scanForReply: Received Packet" << std::endl; + // arrayprinter::print(start, remainingSize); uint16_t apid = tmReader.getModuleApid(); switch (apid) { diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 6d938efe..955484e5 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -68,8 +68,8 @@ ReturnValue_t PlocSupvUartManager::initializeInterface(CookieIF* cookie) { // Use non-canonical mode and clear echo flag tty.c_lflag &= ~(ICANON | ECHO); - // Blocking mode, 0.5 seconds timeout - tty.c_cc[VTIME] = 5; + // Blocking mode, 0.2 seconds timeout + tty.c_cc[VTIME] = 2; tty.c_cc[VMIN] = 0; uart::setBaudrate(tty, uartCookie->getBaudrate()); @@ -429,8 +429,7 @@ ReturnValue_t PlocSupvUartManager::writeUpdatePackets() { update.bytesWritten); return result; } - result = handlePacketTransmissionNoReply(packet); - // result = encodeAndSendPacket(packet.getFullPacket(), packet.getFullPacketLen()); + result = handlePacketTransmissionNoReply(packet, 2000); if (result != returnvalue::OK) { triggerEvent(WRITE_MEMORY_FAILED, buildProgParams1(progPercent, update.sequenceCount), update.bytesWritten); @@ -494,19 +493,6 @@ uint32_t PlocSupvUartManager::buildProgParams1(uint8_t percent, uint16_t seqCoun // return result; // } -ReturnValue_t PlocSupvUartManager::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 PlocSupvUartManager::selectMemory() { ReturnValue_t result = returnvalue::OK; resetSpParams(); @@ -515,7 +501,7 @@ ReturnValue_t PlocSupvUartManager::selectMemory() { if (result != returnvalue::OK) { return result; } - result = handlePacketTransmissionNoReply(packet); + result = handlePacketTransmissionNoReply(packet, 2000); if (result != returnvalue::OK) { return result; } @@ -580,7 +566,6 @@ ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( if (not ackReceived) { retval = handleAckReception(packet, packetLen); if (retval == 1) { - sif::debug << "ACK received" << std::endl; ackReceived = true; packetWasHandled = true; } else if (retval == -1) { @@ -589,7 +574,6 @@ ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( } else { retval = handleExeAckReception(packet, packetLen); if (retval == 1) { - sif::debug << "EXE ACK received" << std::endl; break; } else if (retval == -1) { return returnvalue::FAILED; @@ -601,7 +585,7 @@ ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( decodedRingBuf.deleteData(packetLen); } } else { - TaskFactory::delayTask(50); + TaskFactory::delayTask(20); } if (countdown.hasTimedOut()) { return result::NO_REPLY_TIMEOUT; @@ -777,7 +761,6 @@ ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand(uint8_t failStep) { if (retval == 1) { packetWasHandled = true; exeReceived = true; - break; } else if (retval == -1) { return returnvalue::FAILED; } @@ -795,7 +778,6 @@ ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand(uint8_t failStep) { result = report.verifyCrc(update.crc); if (result == returnvalue::OK) { triggerEvent(SUPV_MEM_CHECK_OK, result); - return result; } else { sif::warning @@ -813,7 +795,7 @@ ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand(uint8_t failStep) { decodedRingBuf.deleteData(packetLen); } } else { - TaskFactory::delayTask(50); + TaskFactory::delayTask(20); } if (ackReceived and exeReceived and checkReplyReceived) { break; @@ -823,7 +805,6 @@ ReturnValue_t PlocSupvUartManager::handleCheckMemoryCommand(uint8_t failStep) { } } return returnvalue::OK; - return result; } uint32_t PlocSupvUartManager::getFileSize(std::string filename) { @@ -963,8 +944,10 @@ ReturnValue_t PlocSupvUartManager::handleRunningLongerRequest() { ReturnValue_t PlocSupvUartManager::encodeAndSendPacket(const uint8_t* sendData, size_t sendLen) { size_t encodedLen = 0; addHdlcFraming(sendData, sendLen, encodedSendBuf.data(), &encodedLen, encodedSendBuf.size()); - sif::debug << "Sending TC" << std::endl; - arrayprinter::print(encodedSendBuf.data(), encodedLen); + 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 diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index d36a9cd4..d9739e44 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -253,6 +253,7 @@ class PlocSupvUartManager : public DeviceCommunicationIF, std::array tmBuf{}; + bool printTc = false; bool debugMode = false; bool timestamping = true; @@ -275,7 +276,7 @@ class PlocSupvUartManager : public DeviceCommunicationIF, ReturnValue_t writeUpdatePackets(); // ReturnValue_t performEventBufferRequest(); ReturnValue_t handlePacketTransmissionNoReply(supv::TcBase& packet, - uint32_t timeoutExecutionReport = 60000); + uint32_t timeoutExecutionReport); int handleAckReception(supv::TcBase& tc, size_t packetLen); int handleExeAckReception(supv::TcBase& tc, size_t packetLen); @@ -310,7 +311,6 @@ class PlocSupvUartManager : public DeviceCommunicationIF, */ 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); diff --git a/tmtc b/tmtc index 70a1d492..292bafa0 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 70a1d49246b5bd5297c22d336e9dd8f58f019f90 +Subproject commit 292bafa0918d386e7f64bf9ed0e114a887420899 From 6766395f4450a1c8c0513611dfbae3742ef3c6e5 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 24 Nov 2022 14:42:17 +0100 Subject: [PATCH 153/176] works, but SW updates hangs at 21504 bytes --- .../devicedefinitions/PlocSupervisorDefinitions.h | 9 ++++++--- linux/devices/ploc/PlocSupvUartMan.cpp | 4 ++-- 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 8c638c83..aad0a4c8 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -1154,8 +1154,11 @@ class WriteMemory : public TcBase { } 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; + } + res = checkSizeAndSerializeHeader(); if (res != returnvalue::OK) { return res; } @@ -1182,7 +1185,7 @@ class WriteMemory : public TcBase { 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, diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 955484e5..919ac2aa 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -429,7 +429,7 @@ ReturnValue_t PlocSupvUartManager::writeUpdatePackets() { update.bytesWritten); return result; } - result = handlePacketTransmissionNoReply(packet, 2000); + result = handlePacketTransmissionNoReply(packet, 5000); if (result != returnvalue::OK) { triggerEvent(WRITE_MEMORY_FAILED, buildProgParams1(progPercent, update.sequenceCount), update.bytesWritten); @@ -443,7 +443,7 @@ ReturnValue_t PlocSupvUartManager::writeUpdatePackets() { #if OBSW_DEBUG_PLOC_SUPERVISOR == 1 progressPrinter.print(update.bytesWritten); #endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ - TaskFactory::delayTask(1); + // TaskFactory::delayTask(1); } return result; } From c731418b65a7d51697b0e4ae0eeb2f49db40f782 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 25 Nov 2022 10:28:20 +0100 Subject: [PATCH 154/176] disable PLOC SUPV for host build --- bsp_hosted/OBSWConfig.h.in | 2 +- tmtc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/bsp_hosted/OBSWConfig.h.in b/bsp_hosted/OBSWConfig.h.in index 9a80286d..f234e795 100644 --- a/bsp_hosted/OBSWConfig.h.in +++ b/bsp_hosted/OBSWConfig.h.in @@ -15,7 +15,7 @@ #define OBSW_ENABLE_TIMERS 1 #define OBSW_ADD_STAR_TRACKER 0 -#define OBSW_ADD_PLOC_SUPERVISOR 1 +#define OBSW_ADD_PLOC_SUPERVISOR 0 #define OBSW_ADD_PLOC_MPSOC 0 #define OBSW_ADD_SUN_SENSORS 0 #define OBSW_ADD_MGT 0 diff --git a/tmtc b/tmtc index 292bafa0..a54ae782 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 292bafa0918d386e7f64bf9ed0e114a887420899 +Subproject commit a54ae782d46f6f405df8e62ab80b556f971df369 From f771fefbc9d22324a1f48645924ba44ea10b1d4d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 25 Nov 2022 11:04:33 +0100 Subject: [PATCH 155/176] rename scheduling file --- bsp_q7s/core/CMakeLists.txt | 2 +- .../core/{InitMission.cpp => scheduling.cpp} | 42 +++++++++---------- bsp_q7s/core/{InitMission.h => scheduling.h} | 4 +- bsp_q7s/obsw.cpp | 4 +- 4 files changed, 25 insertions(+), 27 deletions(-) rename bsp_q7s/core/{InitMission.cpp => scheduling.cpp} (94%) rename bsp_q7s/core/{InitMission.h => scheduling.h} (92%) diff --git a/bsp_q7s/core/CMakeLists.txt b/bsp_q7s/core/CMakeLists.txt index b4050d73..66b65c62 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) diff --git a/bsp_q7s/core/InitMission.cpp b/bsp_q7s/core/scheduling.cpp similarity index 94% rename from bsp_q7s/core/InitMission.cpp rename to bsp_q7s/core/scheduling.cpp index 3b1eb357..f07eda32 100644 --- a/bsp_q7s/core/InitMission.cpp +++ b/bsp_q7s/core/scheduling.cpp @@ -1,4 +1,4 @@ -#include "bsp_q7s/core/InitMission.h" +#include "scheduling.h" #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) { @@ -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,16 +441,15 @@ 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( @@ -530,9 +528,9 @@ void initmission::createPusTasks(TaskFactory& factory, 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 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/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. */ From a20dce5a87ab0a9257732a448e94f8110836035d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 28 Nov 2022 08:48:19 +0100 Subject: [PATCH 156/176] cmakelists fix, bump fsfw --- bsp_q7s/core/CMakeLists.txt | 2 +- fsfw | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/bsp_q7s/core/CMakeLists.txt b/bsp_q7s/core/CMakeLists.txt index 66b65c62..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 scheduling.cpp ObjectFactory.cpp) -target_sources(${SIMPLE_OBSW_NAME} PRIVATE InitMission.cpp) +target_sources(${SIMPLE_OBSW_NAME} PRIVATE scheduling.cpp) diff --git a/fsfw b/fsfw index 160ff799..46a1c2ba 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 160ff799ace61e24708dcf1fdeaf5fafdf23a4ca +Subproject commit 46a1c2bacea142994666b2201acf0246ba0fd0b4 From bd3350c28a0bc6470856f8f5aab69bec89553a19 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 28 Nov 2022 09:38:32 +0100 Subject: [PATCH 157/176] this might be a bug --- linux/devices/devicedefinitions/PlocSupervisorDefinitions.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index aad0a4c8..68ac6447 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -1198,7 +1198,7 @@ class WriteMemory : public TcBase { 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; } From 2338d951c73eb2943af682edc578a4facc9e46f5 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 28 Nov 2022 11:21:12 +0100 Subject: [PATCH 158/176] some more robustness tweaks --- cmake/scripts/cmake-build-cfg.py | 66 +++++++++++++++++--------- linux/devices/ploc/PlocSupvUartMan.cpp | 5 ++ linux/devices/ploc/PlocSupvUartMan.h | 2 +- scripts/q7s-cp.py | 8 ++-- tmtc | 2 +- 5 files changed, 55 insertions(+), 28 deletions(-) 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/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 919ac2aa..890a1240 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -379,6 +379,11 @@ ReturnValue_t PlocSupvUartManager::writeUpdatePackets() { 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; diff --git a/linux/devices/ploc/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index d9739e44..9ebfac02 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -253,7 +253,7 @@ class PlocSupvUartManager : public DeviceCommunicationIF, std::array tmBuf{}; - bool printTc = false; + bool printTc = true; bool debugMode = false; bool timestamping = true; 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/tmtc b/tmtc index a54ae782..a47ca5c9 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit a54ae782d46f6f405df8e62ab80b556f971df369 +Subproject commit a47ca5c901e340f4c07bbb778dd63bb61554dbc4 From 003d37c490571144cc61e3abd3b2a3710437ff17 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 28 Nov 2022 11:21:46 +0100 Subject: [PATCH 159/176] bump fsfw --- fsfw | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fsfw b/fsfw index 46a1c2ba..8eb869e0 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 46a1c2bacea142994666b2201acf0246ba0fd0b4 +Subproject commit 8eb869e073d99e257c6cc62dbf26b4d99422e9b8 From 2c223712ff64db81bf8efd5c995d13becb139de0 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 28 Nov 2022 16:24:18 +0100 Subject: [PATCH 160/176] various fixes and improvements --- common/config/devConf.h | 2 +- .../PlocSupervisorDefinitions.h | 1 + linux/devices/ploc/PlocSupervisorHandler.cpp | 21 ++++++++++++--- linux/devices/ploc/PlocSupvUartMan.cpp | 26 ++++++++++++++----- linux/devices/ploc/PlocSupvUartMan.h | 3 ++- 5 files changed, 41 insertions(+), 12 deletions(-) diff --git a/common/config/devConf.h b/common/config/devConf.h index 931d1ad1..beb01282 100644 --- a/common/config/devConf.h +++ b/common/config/devConf.h @@ -60,7 +60,7 @@ static constexpr UartBaudRate SYRLINKS_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; +static constexpr UartBaudRate PLOC_SUPV_BAUD = UartBaudRate::RATE_921600; static constexpr UartBaudRate STAR_TRACKER_BAUD = UartBaudRate::RATE_921600; } // namespace uart diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 68ac6447..cb0639fa 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -122,6 +122,7 @@ 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 */ enum ReplyId : DeviceCommandId_t { diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index b022f119..08c63b1a 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -411,6 +411,7 @@ void PlocSupervisorHandler::fillCommandAndReplyMap() { insertInCommandMap(SET_GPIO); insertInCommandMap(READ_GPIO); insertInCommandMap(FACTORY_RESET); + insertInCommandMap(MEMORY_CHECK); insertInCommandMap(SET_SHUTDOWN_TIMEOUT); insertInCommandMap(FACTORY_FLASH); insertInCommandMap(SET_ADC_ENABLED_CHANNELS); @@ -421,6 +422,7 @@ void PlocSupervisorHandler::fillCommandAndReplyMap() { // 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); @@ -507,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: @@ -625,10 +637,7 @@ ReturnValue_t PlocSupervisorHandler::scanForReply(const uint8_t* start, size_t r static_cast(supv::tm::MemManId::UPDATE_STATUS_REPORT)) { *foundLen = tmReader.getFullPacketLen(); *foundId = ReplyId::UPDATE_STATUS_REPORT; - // TODO: I think this will be handled by the uart manager? - // Actually, this is a bit tricky. Maybe the lower level will have two separate ring - // buffers, one for internally handled packets and one for packets which are handled - // here? + return OK; } } } @@ -667,6 +676,10 @@ ReturnValue_t PlocSupervisorHandler::interpretDeviceReply(DeviceCommandId_t id, 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; diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index 890a1240..f2ce3b3b 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -116,7 +116,9 @@ ReturnValue_t PlocSupvUartManager::performOperation(uint8_t operationCode) { break; } case InternalState::DEDICATED_REQUEST: { + updateVtime(1); handleRunningLongerRequest(); + updateVtime(2); MutexGuard mg(lock); state = InternalState::DEFAULT; break; @@ -380,9 +382,9 @@ ReturnValue_t PlocSupvUartManager::writeUpdatePackets() { #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; + 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; @@ -553,6 +555,7 @@ ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( return result; } Countdown countdown(timeoutExecutionReport); + dur_millis_t currentDelay = 5; bool ackReceived = false; bool packetWasHandled = false; while (true) { @@ -590,7 +593,10 @@ ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( decodedRingBuf.deleteData(packetLen); } } else { - TaskFactory::delayTask(20); + TaskFactory::delayTask(currentDelay); + if (currentDelay < 20) { + currentDelay *= 2; + } } if (countdown.hasTimedOut()) { return result::NO_REPLY_TIMEOUT; @@ -1095,9 +1101,11 @@ void PlocSupvUartManager::addHdlcFraming(const uint8_t* src, size_t slen, uint8_ } size_t dummy = 0; + uint8_t crcRaw[2]; // hdlc crc16 is in little endian format - SerializeAdapter::serialize(&crc16, dst + tlen, &dummy, maxDest, SerializeIF::Endianness::LITTLE); - tlen += dummy; + 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; @@ -1141,3 +1149,9 @@ 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/PlocSupvUartMan.h b/linux/devices/ploc/PlocSupvUartMan.h index 9ebfac02..e1539c97 100644 --- a/linux/devices/ploc/PlocSupvUartMan.h +++ b/linux/devices/ploc/PlocSupvUartMan.h @@ -253,7 +253,7 @@ class PlocSupvUartManager : public DeviceCommunicationIF, std::array tmBuf{}; - bool printTc = true; + bool printTc = false; bool debugMode = false; bool timestamping = true; @@ -368,6 +368,7 @@ class PlocSupvUartManager : public DeviceCommunicationIF, 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_ */ From 425e7c1e520a778f8cc896f06d0a03b8872e172a Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 28 Nov 2022 16:27:33 +0100 Subject: [PATCH 161/176] increase regular delay to up to 80 ms --- linux/devices/ploc/PlocSupvUartMan.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index f2ce3b3b..ee232f47 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -594,7 +594,7 @@ ReturnValue_t PlocSupvUartManager::handlePacketTransmissionNoReply( } } else { TaskFactory::delayTask(currentDelay); - if (currentDelay < 20) { + if (currentDelay < 80) { currentDelay *= 2; } } From acc77399587144974c21544c5b04a5fe397248ba Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 28 Nov 2022 16:33:50 +0100 Subject: [PATCH 162/176] bump changelog --- CHANGELOG.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 6dd1f9da..ba0e0641 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -13,7 +13,9 @@ list yields a list of all related PRs for each release. ## Added - PLOC Supervisor Update: Update SW to use newest PLOC SUPV version by TAS - PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/316 + 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 From 0763f11998d9796697d4ca808369187b4db2e3da Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 28 Nov 2022 18:21:53 +0100 Subject: [PATCH 163/176] revert baud rate --- common/config/devConf.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/config/devConf.h b/common/config/devConf.h index beb01282..931d1ad1 100644 --- a/common/config/devConf.h +++ b/common/config/devConf.h @@ -60,7 +60,7 @@ static constexpr UartBaudRate SYRLINKS_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_921600; +static constexpr UartBaudRate PLOC_SUPV_BAUD = UartBaudRate::RATE_115200; static constexpr UartBaudRate STAR_TRACKER_BAUD = UartBaudRate::RATE_921600; } // namespace uart From 87ab84c649559f4bfcfcfb2cf78d69ccbe7f2edd Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 28 Nov 2022 18:23:55 +0100 Subject: [PATCH 164/176] bump changelog --- CHANGELOG.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index ba0e0641..52b2d1a0 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -10,6 +10,12 @@ 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 From 5ba5e69273223726d3286db17c2c1afcc5275d36 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 28 Nov 2022 18:25:08 +0100 Subject: [PATCH 165/176] re-run generators --- generators/bsp_q7s_events.csv | 2 +- generators/bsp_q7s_returnvalues.csv | 660 +++++++++--------- generators/events/translateEvents.cpp | 6 +- generators/objects/translateObjects.cpp | 2 +- linux/fsfwconfig/events/translateEvents.cpp | 6 +- linux/fsfwconfig/objects/translateObjects.cpp | 2 +- tmtc | 2 +- 7 files changed, 340 insertions(+), 340 deletions(-) diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index 9a89eca9..e56b0ed6 100644 --- a/generators/bsp_q7s_events.csv +++ b/generators/bsp_q7s_events.csv @@ -129,7 +129,7 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 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_SHUWDOWN_BUILD_FAILED;LOW;Failed to build the command to shutdown the MPSoC;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 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 ac00745c..fdcc4488 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** * @brief Auto-generated event translation file. Contains 239 translations. * @details - * Generated on: 2022-11-16 15:25:08 + * Generated on: 2022-11-28 18:24:37 */ #include "translateEvents.h" @@ -135,7 +135,7 @@ 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 *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"; @@ -504,7 +504,7 @@ const char *translateEvents(Event event) { case (12007): return SUPV_HELPER_EXECUTING_STRING; case (12008): - return SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING; + return SUPV_MPSOC_SHUTDOWN_BUILD_FAILED_STRING; case (12100): return SANITIZATION_FAILED_STRING; case (12101): diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index 0890725e..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-16 15:25:08 + * Generated on: 2022-11-28 18:24:37 */ #include "translateObjects.h" diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index ac00745c..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 239 translations. * @details - * Generated on: 2022-11-16 15:25:08 + * Generated on: 2022-11-28 18:24:37 */ #include "translateEvents.h" @@ -135,7 +135,7 @@ 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 *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"; @@ -504,7 +504,7 @@ const char *translateEvents(Event event) { case (12007): return SUPV_HELPER_EXECUTING_STRING; case (12008): - return SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING; + return SUPV_MPSOC_SHUTDOWN_BUILD_FAILED_STRING; case (12100): return SANITIZATION_FAILED_STRING; case (12101): diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index 0890725e..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-16 15:25:08 + * Generated on: 2022-11-28 18:24:37 */ #include "translateObjects.h" diff --git a/tmtc b/tmtc index a47ca5c9..12f7b5bb 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit a47ca5c901e340f4c07bbb778dd63bb61554dbc4 +Subproject commit 12f7b5bb258f183b62a2ed27776d2385a728306e From 44ef698c3520a9251fb5745702bfb0256b2d9ca3 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 28 Nov 2022 18:27:59 +0100 Subject: [PATCH 166/176] bump version --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 765f1fc9..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) From b0f000a42f3f6b44aa0ababf205d94ed3cd4b312 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 28 Nov 2022 18:31:44 +0100 Subject: [PATCH 167/176] new PLOC SUPV baudrate 921600 --- common/config/devConf.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/common/config/devConf.h b/common/config/devConf.h index 931d1ad1..beb01282 100644 --- a/common/config/devConf.h +++ b/common/config/devConf.h @@ -60,7 +60,7 @@ static constexpr UartBaudRate SYRLINKS_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; +static constexpr UartBaudRate PLOC_SUPV_BAUD = UartBaudRate::RATE_921600; static constexpr UartBaudRate STAR_TRACKER_BAUD = UartBaudRate::RATE_921600; } // namespace uart From ffbf7df55792738c10666b0e0ebe43406d6b3980 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 29 Nov 2022 11:05:19 +0100 Subject: [PATCH 168/176] rename ploc supv and i2c dev symlinks --- bsp_q7s/boardconfig/busConf.h | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/bsp_q7s/boardconfig/busConf.h b/bsp_q7s/boardconfig/busConf.h index 7b50af4e..a094c029 100644 --- a/bsp_q7s/boardconfig/busConf.h +++ b/bsp_q7s/boardconfig/busConf.h @@ -8,12 +8,14 @@ static constexpr uint32_t SPI_MAIN_BUS_LOCK_TIMEOUT = 50; static constexpr char SPI_RW_DEV[] = "/dev/spi_rw"; -static constexpr char I2C_PL_EIVE[] = "/dev/i2c_eive"; -static constexpr char I2C_PS_EIVE[] = "/dev/i2c-2"; +//! I2C bus using an I2C IP core in the programmable logic (PL) +static constexpr char I2C_PL_EIVE[] = "/dev/i2c_pl"; +//! I2C bus using the I2C peripheral of the ARM processing system (PS) +static constexpr char I2C_PS_EIVE[] = "/dev/i2c_ps"; static constexpr char UART_GNSS_DEV[] = "/dev/gps0"; static constexpr char UART_PLOC_MPSOC_DEV[] = "/dev/ul_plmpsoc"; -static constexpr char UART_PLOC_SUPERVSIOR_DEV[] = "/dev/ul_plsv"; +static constexpr char UART_PLOC_SUPERVSIOR_DEV[] = "/dev/ploc_supv"; static constexpr char UART_SYRLINKS_DEV[] = "/dev/ul_syrlinks"; static constexpr char UART_STAR_TRACKER_DEV[] = "/dev/ul_str"; static constexpr char UART_SCEX_DEV[] = "/dev/scex"; From d4acdb67bb4a7464a9479fa27a0bd41fa6c2b4ad Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 29 Nov 2022 11:07:02 +0100 Subject: [PATCH 169/176] bump changelog --- CHANGELOG.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/CHANGELOG.md b/CHANGELOG.md index 52b2d1a0..b9675d21 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -13,6 +13,8 @@ list yields a list of all related PRs for each release. ## Changed - PLOC Supervisor: Changes baudrate to 921600 +- Renamed `/dev/ul-plsv` to `/dev/ploc_supv`, is not a UART lite anymore +- Renamed `/dev/i2c_eive` to `/dev/i2c_pl` and `/dev/i2c-2` to `/dev/i2c_ps`. # [v1.17.0] 28.11.2022 From a1c9fece1e1887305b4f28e42adc3a0454580dcc Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 29 Nov 2022 11:08:34 +0100 Subject: [PATCH 170/176] bump changelog --- CHANGELOG.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index b9675d21..a4df75d5 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -15,7 +15,7 @@ list yields a list of all related PRs for each release. - PLOC Supervisor: Changes baudrate to 921600 - Renamed `/dev/ul-plsv` to `/dev/ploc_supv`, is not a UART lite anymore - Renamed `/dev/i2c_eive` to `/dev/i2c_pl` and `/dev/i2c-2` to `/dev/i2c_ps`. - + PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/328 # [v1.17.0] 28.11.2022 ## Added From fbf8f5ef6cdded72548fe6bac45b503d24dc1fd5 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 29 Nov 2022 16:55:55 +0100 Subject: [PATCH 171/176] bump tmtc --- generators/events/event_parser.py | 2 +- generators/objects/objects.py | 2 +- generators/returnvalues/returnvalues_parser.py | 2 +- tmtc | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/generators/events/event_parser.py b/generators/events/event_parser.py index 8ab88a1b..8c5ab35b 100644 --- a/generators/events/event_parser.py +++ b/generators/events/event_parser.py @@ -46,7 +46,7 @@ BSP_DIR_NAME = BSP_SELECT.value # Store this file in the root of the generators folder CSV_FILENAME = Path(f"{ROOT_DIR}/{BSP_SELECT.value}_events.csv") -CSV_COPY_DEST = Path(f"{OBSW_ROOT_DIR}/tmtc/config/events.csv") +CSV_COPY_DEST = Path(f"{OBSW_ROOT_DIR}/tmtc/eive_tmtc/config/events.csv") if BSP_SELECT == BspType.BSP_Q7S or BSP_SELECT == BspType.BSP_LINUX_BOARD: FSFW_CONFIG_ROOT = Path(f"{OBSW_ROOT_DIR}/linux/fsfwconfig") diff --git a/generators/objects/objects.py b/generators/objects/objects.py index c64a61ed..af8fec4b 100644 --- a/generators/objects/objects.py +++ b/generators/objects/objects.py @@ -43,7 +43,7 @@ CPP_COPY_DESTINATION = f"{FSFW_CONFIG_ROOT}/objects/" CPP_FILENAME = f"{os.path.dirname(os.path.realpath(__file__))}//translateObjects.cpp" CPP_H_FILENAME = f"{os.path.dirname(os.path.realpath(__file__))}//translateObjects.h" CSV_OBJECT_FILENAME = f"{ROOT_DIR}/{BSP_SELECT.value}_objects.csv" -CSV_COPY_DEST = f"{OBSW_ROOT_DIR}/tmtc/config/objects.csv" +CSV_COPY_DEST = f"{OBSW_ROOT_DIR}/tmtc/eive_tmtc/config/objects.csv" FILE_SEPARATOR = ";" diff --git a/generators/returnvalues/returnvalues_parser.py b/generators/returnvalues/returnvalues_parser.py index e79f79de..4f6f30e1 100644 --- a/generators/returnvalues/returnvalues_parser.py +++ b/generators/returnvalues/returnvalues_parser.py @@ -31,7 +31,7 @@ MAX_STRING_LENGTH = 32 BSP_SELECT = BspType.BSP_Q7S BSP_DIR_NAME = BSP_SELECT.value CSV_RETVAL_FILENAME = Path(f"{ROOT_DIR}/{BSP_SELECT.value}_returnvalues.csv") -CSV_COPY_DEST = Path(f"{OBSW_ROOT_DIR}/tmtc/config/returnvalues.csv") +CSV_COPY_DEST = Path(f"{OBSW_ROOT_DIR}/tmtc/eive_tmtc/config/returnvalues.csv") ADD_LINUX_FOLDER = False if BSP_SELECT == BspType.BSP_Q7S or BSP_SELECT == BspType.BSP_LINUX_BOARD: diff --git a/tmtc b/tmtc index 12f7b5bb..1483dc4d 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 12f7b5bb258f183b62a2ed27776d2385a728306e +Subproject commit 1483dc4d93898826b1cee645148f88995bbdc7a5 From 2b327bf3a7f6a12867ef565271f56d16eb4bea76 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 29 Nov 2022 23:09:55 +0100 Subject: [PATCH 172/176] initialize a variable --- linux/devices/ploc/PlocSupvUartMan.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/linux/devices/ploc/PlocSupvUartMan.cpp b/linux/devices/ploc/PlocSupvUartMan.cpp index ee232f47..a246d97c 100644 --- a/linux/devices/ploc/PlocSupvUartMan.cpp +++ b/linux/devices/ploc/PlocSupvUartMan.cpp @@ -1132,7 +1132,7 @@ int PlocSupvUartManager::removeHdlcFramingWithCrcCheck(const uint8_t* src, size_ } // calc crc16 uint16_t calcCrc = calc_crc16_buff_reflected(dst, tlen - 2); - uint16_t crc; + uint16_t crc = 0; size_t dummy; SerializeAdapter::deSerialize(&crc, dst + tlen - 2, &dummy, SerializeIF::Endianness::LITTLE); if (calcCrc != crc) { From 84a3466b4d6dafa1b5526bc2f653df16ada91de5 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 29 Nov 2022 23:24:45 +0100 Subject: [PATCH 173/176] fixed array list min len 1 --- fsfw | 2 +- mission/system/tree/acsModeTree.cpp | 2 +- mission/system/tree/payloadModeTree.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/fsfw b/fsfw index 8eb869e0..5b0ea912 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 8eb869e073d99e257c6cc62dbf26b4d99422e9b8 +Subproject commit 5b0ea91222a6b8efb2f4562cfecbcb735dfeedd5 diff --git a/mission/system/tree/acsModeTree.cpp b/mission/system/tree/acsModeTree.cpp index 4e390985..d91c59fc 100644 --- a/mission/system/tree/acsModeTree.cpp +++ b/mission/system/tree/acsModeTree.cpp @@ -30,7 +30,7 @@ static const auto NML = DeviceHandlerIF::MODE_NORMAL; auto ACS_SEQUENCE_OFF = std::make_pair(acs::CtrlModes::OFF << 24, FixedArrayList()); auto ACS_TABLE_OFF_TGT = - std::make_pair((acs::CtrlModes::OFF << 24) | 1, FixedArrayList()); + std::make_pair((acs::CtrlModes::OFF << 24) | 1, FixedArrayList()); auto ACS_TABLE_OFF_TRANS = std::make_pair((acs::CtrlModes::OFF << 24) | 2, FixedArrayList()); diff --git a/mission/system/tree/payloadModeTree.cpp b/mission/system/tree/payloadModeTree.cpp index 6cbc4004..0396cfc6 100644 --- a/mission/system/tree/payloadModeTree.cpp +++ b/mission/system/tree/payloadModeTree.cpp @@ -28,7 +28,7 @@ static const auto ON = HasModesIF::MODE_ON; static const auto NML = DeviceHandlerIF::MODE_NORMAL; auto PL_SEQUENCE_OFF = std::make_pair(OFF << 24, FixedArrayList()); -auto PL_TABLE_OFF_TGT = std::make_pair((OFF << 24) | 1, FixedArrayList()); +auto PL_TABLE_OFF_TGT = std::make_pair((OFF << 24) | 1, FixedArrayList()); auto PL_TABLE_OFF_TRANS_0 = std::make_pair((OFF << 24) | 2, FixedArrayList()); auto PL_TABLE_OFF_TRANS_1 = std::make_pair((OFF << 24) | 3, FixedArrayList()); From 5f929f6cf805fff498a5d4d49ef4c65f765a1059 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 30 Nov 2022 17:26:33 +0100 Subject: [PATCH 174/176] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 1483dc4d..c421f3f5 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 1483dc4d93898826b1cee645148f88995bbdc7a5 +Subproject commit c421f3f5d78d77d23e42d1ccae79d7c6fc308431 From f73d293cdd72653bef7b3ffe82bb815f9ff3676a Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 30 Nov 2022 18:08:16 +0100 Subject: [PATCH 175/176] schedule PL task --- bsp_q7s/core/scheduling.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/bsp_q7s/core/scheduling.cpp b/bsp_q7s/core/scheduling.cpp index f07eda32..5a8c3827 100644 --- a/bsp_q7s/core/scheduling.cpp +++ b/bsp_q7s/core/scheduling.cpp @@ -365,6 +365,7 @@ void scheduling::initTasks() { #if OBSW_ADD_PLOC_SUPERVISOR == 1 supvHelperTask->startTask(); #endif /* OBSW_ADD_PLOC_SUPERVISOR == 1 */ + plTask->startTask(); #if OBSW_ADD_TEST_CODE == 1 taskStarter(testTasks, "Test task vector"); From d3252434aa88fe5d0aead95acee7bfcf9e799e8a Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 1 Dec 2022 14:47:21 +0100 Subject: [PATCH 176/176] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 1483dc4d..6308bbb3 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 1483dc4d93898826b1cee645148f88995bbdc7a5 +Subproject commit 6308bbb3f0e4387508371bd3d18c52f404c4e18b