From 4a28f79e3af0c6e16ae1deee4eb81d8f3aaeb73f Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 15 Aug 2022 11:57:57 +0200 Subject: [PATCH 01/58] updates for new API --- fsfw | 2 +- mission/controller/AcsController.h | 1 + mission/controller/ThermalController.cpp | 10 ++++++---- mission/core/GenericFactory.cpp | 21 ++++++++++---------- mission/devices/ACUHandler.cpp | 6 ++++-- mission/devices/BpxBatteryHandler.cpp | 3 ++- mission/devices/GyroADIS1650XHandler.cpp | 3 ++- mission/devices/IMTQHandler.cpp | 9 ++++++--- mission/devices/Max31865EiveHandler.cpp | 3 ++- mission/devices/Max31865PT1000Handler.cpp | 3 ++- mission/devices/P60DockHandler.cpp | 6 ++++-- mission/devices/PCDUHandler.cpp | 3 ++- mission/devices/PCDUHandler.h | 2 +- mission/devices/PDU1Handler.cpp | 6 ++++-- mission/devices/PDU2Handler.cpp | 6 ++++-- mission/devices/PayloadPcduHandler.cpp | 3 ++- mission/devices/RadiationSensorHandler.cpp | 3 ++- mission/devices/RwHandler.cpp | 9 ++++++--- mission/devices/SusHandler.cpp | 3 ++- mission/devices/SyrlinksHkHandler.cpp | 9 ++++++--- mission/devices/Tmp1075Handler.cpp | 3 ++- mission/tmtc/TmFunnel.cpp | 23 ++++++++++++++-------- mission/tmtc/TmFunnel.h | 4 +++- 23 files changed, 89 insertions(+), 52 deletions(-) diff --git a/fsfw b/fsfw index f4c4f994..007f958a 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit f4c4f9946c7fb9fd050178baa4865da654366b70 +Subproject commit 007f958a0b787a572bf1bd98b348c3a632799bf7 diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index 35503c48..c5b43288 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -45,6 +45,7 @@ class AcsController : public ExtendedControllerBase { PoolEntry mgm3PoolVec = PoolEntry(3); PoolEntry imtqMgmPoolVec = PoolEntry(3); PoolEntry imtqCalActStatus = PoolEntry(); + void copyMgmData(); // Initial delay to make sure all pool variables have been initialized their owners diff --git a/mission/controller/ThermalController.cpp b/mission/controller/ThermalController.cpp index 9e0fbd5a..abb46f48 100644 --- a/mission/controller/ThermalController.cpp +++ b/mission/controller/ThermalController.cpp @@ -200,10 +200,12 @@ ReturnValue_t ThermalController::initializeLocalDataPool(localpool::DataPool& lo localDataPoolMap.emplace(thermalControllerDefinitions::TEMP_ADC_PAYLOAD_PCDU, new PoolEntry({0.0})); - poolManager.subscribeForPeriodicPacket(sensorTemperatures.getSid(), false, 1.0, false); - poolManager.subscribeForPeriodicPacket(susTemperatures.getSid(), false, 1.0, false); - poolManager.subscribeForPeriodicPacket(deviceTemperatures.getSid(), false, 1.0, false); - + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(sensorTemperatures.getSid(), false, 10.0)); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(susTemperatures.getSid(), false, 10.0)); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(deviceTemperatures.getSid(), false, 10.0)); return RETURN_OK; } diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index 1be91594..fbfb16f2 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -15,8 +15,8 @@ #include #include #include -#include -#include +#include +#include #include #include "OBSWConfig.h" @@ -54,7 +54,7 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_) { *healthTable_ = healthTable; } new InternalErrorReporter(objects::INTERNAL_ERROR_REPORTER); - new TimeStamper(objects::TIME_STAMPER); + auto* timeStamper = new CdsShortTimeStamper(objects::TIME_STAMPER); { PoolManager::LocalPoolConfig poolCfg = {{300, 16}, {300, 32}, {200, 64}, @@ -75,15 +75,14 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_) { } auto* ccsdsDistrib = new CCSDSDistributor(apid::EIVE_OBSW, objects::CCSDS_PACKET_DISTRIBUTOR); - new PUSDistributor(apid::EIVE_OBSW, objects::PUS_PACKET_DISTRIBUTOR, - objects::CCSDS_PACKET_DISTRIBUTOR); + new PusDistributor(apid::EIVE_OBSW, objects::PUS_PACKET_DISTRIBUTOR, ccsdsDistrib); uint8_t vc = 0; #if OBSW_TM_TO_PTME == 1 vc = config::LIVE_TM; #endif // Every TM packet goes through this funnel - new TmFunnel(objects::TM_FUNNEL, 50, vc); + new TmFunnel(objects::TM_FUNNEL, *timeStamper, 50, vc); // PUS service stack new Service1TelecommandVerification(objects::PUS_SERVICE_1_VERIFICATION, apid::EIVE_OBSW, @@ -92,15 +91,15 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_) { pus::PUS_SERVICE_2, 3, 10); new Service3Housekeeping(objects::PUS_SERVICE_3_HOUSEKEEPING, apid::EIVE_OBSW, pus::PUS_SERVICE_3); - new Service5EventReporting(objects::PUS_SERVICE_5_EVENT_REPORTING, apid::EIVE_OBSW, - pus::PUS_SERVICE_5, 15, 45); + new Service5EventReporting(PsbParams(objects::PUS_SERVICE_5_EVENT_REPORTING, apid::EIVE_OBSW, + pus::PUS_SERVICE_5), 15, 45); new Service8FunctionManagement(objects::PUS_SERVICE_8_FUNCTION_MGMT, apid::EIVE_OBSW, pus::PUS_SERVICE_8, 3, 60); - new Service9TimeManagement(objects::PUS_SERVICE_9_TIME_MGMT, apid::EIVE_OBSW, pus::PUS_SERVICE_9); + new Service9TimeManagement(PsbParams(objects::PUS_SERVICE_9_TIME_MGMT, apid::EIVE_OBSW, pus::PUS_SERVICE_9)); new Service11TelecommandScheduling( - objects::PUS_SERVICE_11_TC_SCHEDULER, apid::EIVE_OBSW, pus::PUS_SERVICE_11, ccsdsDistrib); - new Service17Test(objects::PUS_SERVICE_17_TEST, apid::EIVE_OBSW, pus::PUS_SERVICE_17); + PsbParams(objects::PUS_SERVICE_11_TC_SCHEDULER, apid::EIVE_OBSW, pus::PUS_SERVICE_11), ccsdsDistrib); + new Service17Test(PsbParams(objects::PUS_SERVICE_17_TEST, apid::EIVE_OBSW, pus::PUS_SERVICE_17)); new Service20ParameterManagement(objects::PUS_SERVICE_20_PARAMETERS, apid::EIVE_OBSW, pus::PUS_SERVICE_20); new CService200ModeCommanding(objects::PUS_SERVICE_200_MODE_MGMT, apid::EIVE_OBSW, diff --git a/mission/devices/ACUHandler.cpp b/mission/devices/ACUHandler.cpp index c62b7b0d..35f8e2dd 100644 --- a/mission/devices/ACUHandler.cpp +++ b/mission/devices/ACUHandler.cpp @@ -170,8 +170,10 @@ ReturnValue_t ACUHandler::initializeLocalDataPool(localpool::DataPool &localData localDataPoolMap.emplace(pool::ACU_WDT_CNT_GND, new PoolEntry({0})); localDataPoolMap.emplace(pool::ACU_WDT_GND_LEFT, new PoolEntry({0})); - poolManager.subscribeForPeriodicPacket(coreHk.getSid(), false, 10.0, true); - poolManager.subscribeForPeriodicPacket(auxHk.getSid(), false, 30.0, false); + poolManager.subscribeForDiagPeriodicPacket( + subdp::DiagnosticsHkPeriodicParams(coreHk.getSid(), false, 10.0)); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(auxHk.getSid(), false, 30.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/BpxBatteryHandler.cpp b/mission/devices/BpxBatteryHandler.cpp index 4ae7b962..d121fc8c 100644 --- a/mission/devices/BpxBatteryHandler.cpp +++ b/mission/devices/BpxBatteryHandler.cpp @@ -270,7 +270,8 @@ ReturnValue_t BpxBatteryHandler::initializeLocalDataPool(localpool::DataPool& lo localDataPoolMap.emplace(BpxBattery::BATTERY_HEATER_MODE, &battheatMode); localDataPoolMap.emplace(BpxBattery::BATTHEAT_LOW_LIMIT, &battheatLow); localDataPoolMap.emplace(BpxBattery::BATTHEAT_HIGH_LIMIT, &battheatHigh); - poolManager.subscribeForPeriodicPacket(hkSet.getSid(), false, 30.0, false); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(hkSet.getSid(), false, 30.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/GyroADIS1650XHandler.cpp b/mission/devices/GyroADIS1650XHandler.cpp index 77862bfb..3e798f04 100644 --- a/mission/devices/GyroADIS1650XHandler.cpp +++ b/mission/devices/GyroADIS1650XHandler.cpp @@ -363,7 +363,8 @@ ReturnValue_t GyroADIS1650XHandler::initializeLocalDataPool(localpool::DataPool localDataPoolMap.emplace(ADIS1650X::FILTER_SETTINGS, new PoolEntry()); localDataPoolMap.emplace(ADIS1650X::MSC_CTRL_REGISTER, new PoolEntry()); localDataPoolMap.emplace(ADIS1650X::DEC_RATE_REGISTER, new PoolEntry()); - poolManager.subscribeForPeriodicPacket(primaryDataset.getSid(), false, 5.0, true); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(primaryDataset.getSid(), false, 5.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/IMTQHandler.cpp b/mission/devices/IMTQHandler.cpp index ea7a3177..98b67e96 100644 --- a/mission/devices/IMTQHandler.cpp +++ b/mission/devices/IMTQHandler.cpp @@ -604,9 +604,12 @@ ReturnValue_t IMTQHandler::initializeLocalDataPool(localpool::DataPool& localDat localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_Y_TEMPERATURE, new PoolEntry({0})); localDataPoolMap.emplace(IMTQ::FINA_NEG_Z_COIL_Z_TEMPERATURE, new PoolEntry({0})); - poolManager.subscribeForPeriodicPacket(engHkDataset.getSid(), false, 10.0, true); - poolManager.subscribeForPeriodicPacket(calMtmMeasurementSet.getSid(), false, 10.0, true); - poolManager.subscribeForPeriodicPacket(rawMtmMeasurementSet.getSid(), false, 10.0, true); + poolManager.subscribeForDiagPeriodicPacket( + subdp::DiagnosticsHkPeriodicParams(engHkDataset.getSid(), false, 10.0)); + poolManager.subscribeForDiagPeriodicPacket( + subdp::DiagnosticsHkPeriodicParams(calMtmMeasurementSet.getSid(), false, 10.0)); + poolManager.subscribeForDiagPeriodicPacket( + subdp::DiagnosticsHkPeriodicParams(rawMtmMeasurementSet.getSid(), false, 10.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/Max31865EiveHandler.cpp b/mission/devices/Max31865EiveHandler.cpp index 6f6760ad..7ad15670 100644 --- a/mission/devices/Max31865EiveHandler.cpp +++ b/mission/devices/Max31865EiveHandler.cpp @@ -184,7 +184,8 @@ ReturnValue_t Max31865EiveHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap.emplace(static_cast(PoolIds::LAST_FAULT_BYTE), new PoolEntry({0})); localDataPoolMap.emplace(static_cast(PoolIds::FAULT_BYTE), new PoolEntry({0})); - poolManager.subscribeForPeriodicPacket(sensorDataset.getSid(), false, 30.0, false); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(sensorDataset.getSid(), false, 30.0)); return RETURN_OK; } diff --git a/mission/devices/Max31865PT1000Handler.cpp b/mission/devices/Max31865PT1000Handler.cpp index 354fe1c5..a5f6aa4f 100644 --- a/mission/devices/Max31865PT1000Handler.cpp +++ b/mission/devices/Max31865PT1000Handler.cpp @@ -514,7 +514,8 @@ ReturnValue_t Max31865PT1000Handler::initializeLocalDataPool(localpool::DataPool localDataPoolMap.emplace(static_cast(PoolIds::LAST_FAULT_BYTE), new PoolEntry({0})); localDataPoolMap.emplace(static_cast(PoolIds::FAULT_BYTE), new PoolEntry({0})); - poolManager.subscribeForPeriodicPacket(sensorDataset.getSid(), false, 30.0, false); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(sensorDataset.getSid(), false, 30.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/P60DockHandler.cpp b/mission/devices/P60DockHandler.cpp index 975e069d..f059a1d7 100644 --- a/mission/devices/P60DockHandler.cpp +++ b/mission/devices/P60DockHandler.cpp @@ -225,8 +225,10 @@ ReturnValue_t P60DockHandler::initializeLocalDataPool(localpool::DataPool &local localDataPoolMap.emplace(pool::P60DOCK_ANT6_DEPL, new PoolEntry({0})); localDataPoolMap.emplace(pool::P60DOCK_AR6_DEPL, new PoolEntry({0})); - poolManager.subscribeForPeriodicPacket(coreHk.getSid(), false, 10.0, false); - poolManager.subscribeForPeriodicPacket(auxHk.getSid(), false, 30.0, false); + poolManager.subscribeForDiagPeriodicPacket( + subdp::DiagnosticsHkPeriodicParams(coreHk.getSid(), false, 10.0)); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(auxHk.getSid(), false, 30.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/PCDUHandler.cpp b/mission/devices/PCDUHandler.cpp index 8e9f1918..70952cea 100644 --- a/mission/devices/PCDUHandler.cpp +++ b/mission/devices/PCDUHandler.cpp @@ -394,7 +394,8 @@ ReturnValue_t PCDUHandler::initializeLocalDataPool(localpool::DataPool& localDat using namespace pcdu; localDataPoolMap.emplace(PoolIds::PDU1_SWITCHES, &pdu1Switches); localDataPoolMap.emplace(PoolIds::PDU2_SWITCHES, &pdu2Switches); - poolManager.subscribeForPeriodicPacket(switcherSet.getSid(), false, 5.0, true); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(switcherSet.getSid(), false, 5.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/PCDUHandler.h b/mission/devices/PCDUHandler.h index 8f589751..98be1f38 100644 --- a/mission/devices/PCDUHandler.h +++ b/mission/devices/PCDUHandler.h @@ -31,7 +31,7 @@ class PCDUHandler : public PowerSwitchIF, virtual ReturnValue_t initialize() override; virtual ReturnValue_t performOperation(uint8_t counter) override; virtual void handleChangedDataset(sid_t sid, - store_address_t storeId = storeId::INVALID_STORE_ADDRESS, + store_address_t storeId = store_address_t::invalid(), bool* clearMessage = nullptr) override; virtual ReturnValue_t sendSwitchCommand(uint8_t switchNr, ReturnValue_t onOff) override; diff --git a/mission/devices/PDU1Handler.cpp b/mission/devices/PDU1Handler.cpp index fca0fbeb..9c2f845c 100644 --- a/mission/devices/PDU1Handler.cpp +++ b/mission/devices/PDU1Handler.cpp @@ -86,8 +86,10 @@ void PDU1Handler::parseHkTableReply(const uint8_t *packet) { ReturnValue_t PDU1Handler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { initializePduPool(localDataPoolMap, poolManager, pcdu::INIT_SWITCHES_PDU1); - poolManager.subscribeForPeriodicPacket(coreHk.getSid(), false, 10.0, true); - poolManager.subscribeForPeriodicPacket(auxHk.getSid(), false, 30.0, false); + poolManager.subscribeForDiagPeriodicPacket( + subdp::DiagnosticsHkPeriodicParams(coreHk.getSid(), false, 10.0)); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(auxHk.getSid(), false, 30.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/PDU2Handler.cpp b/mission/devices/PDU2Handler.cpp index d0cef3f5..073ccb23 100644 --- a/mission/devices/PDU2Handler.cpp +++ b/mission/devices/PDU2Handler.cpp @@ -49,8 +49,10 @@ void PDU2Handler::parseHkTableReply(const uint8_t *packet) { ReturnValue_t PDU2Handler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { initializePduPool(localDataPoolMap, poolManager, pcdu::INIT_SWITCHES_PDU2); - poolManager.subscribeForPeriodicPacket(coreHk.getSid(), false, 10.0, true); - poolManager.subscribeForPeriodicPacket(auxHk.getSid(), false, 30.0, false); + poolManager.subscribeForDiagPeriodicPacket( + subdp::DiagnosticsHkPeriodicParams(coreHk.getSid(), false, 10.0)); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(auxHk.getSid(), false, 30.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/PayloadPcduHandler.cpp b/mission/devices/PayloadPcduHandler.cpp index 3e18a94e..d45b2c95 100644 --- a/mission/devices/PayloadPcduHandler.cpp +++ b/mission/devices/PayloadPcduHandler.cpp @@ -295,7 +295,8 @@ ReturnValue_t PayloadPcduHandler::initializeLocalDataPool(localpool::DataPool& l localDataPoolMap.emplace(plpcdu::PlPcduPoolIds::CHANNEL_VEC, &channelValues); localDataPoolMap.emplace(plpcdu::PlPcduPoolIds::PROCESSED_VEC, &processedValues); localDataPoolMap.emplace(plpcdu::PlPcduPoolIds::TEMP, &tempC); - poolManager.subscribeForPeriodicPacket(adcSet.getSid(), false, 5.0, true); + poolManager.subscribeForDiagPeriodicPacket( + subdp::DiagnosticsHkPeriodicParams(adcSet.getSid(), false, 5.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/RadiationSensorHandler.cpp b/mission/devices/RadiationSensorHandler.cpp index d94e9197..716b54a5 100644 --- a/mission/devices/RadiationSensorHandler.cpp +++ b/mission/devices/RadiationSensorHandler.cpp @@ -204,7 +204,8 @@ ReturnValue_t RadiationSensorHandler::initializeLocalDataPool(localpool::DataPoo localDataPoolMap.emplace(RAD_SENSOR::AIN5, new PoolEntry({0})); localDataPoolMap.emplace(RAD_SENSOR::AIN6, new PoolEntry({0})); localDataPoolMap.emplace(RAD_SENSOR::AIN7, new PoolEntry({0})); - poolManager.subscribeForPeriodicPacket(dataset.getSid(), false, 20.0, false); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(dataset.getSid(), false, 20.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/RwHandler.cpp b/mission/devices/RwHandler.cpp index e8e04932..44dbac0d 100644 --- a/mission/devices/RwHandler.cpp +++ b/mission/devices/RwHandler.cpp @@ -277,9 +277,12 @@ ReturnValue_t RwHandler::initializeLocalDataPool(localpool::DataPool& localDataP localDataPoolMap.emplace(RwDefinitions::SPI_BYTES_READ, new PoolEntry({0})); localDataPoolMap.emplace(RwDefinitions::SPI_REG_OVERRUN_ERRORS, new PoolEntry({0})); localDataPoolMap.emplace(RwDefinitions::SPI_TOTAL_ERRORS, new PoolEntry({0})); - poolManager.subscribeForPeriodicPacket(statusSet.getSid(), false, 5.0, true); - poolManager.subscribeForPeriodicPacket(tmDataset.getSid(), false, 30.0, false); - poolManager.subscribeForPeriodicPacket(lastResetStatusSet.getSid(), false, 30.0, false); + poolManager.subscribeForDiagPeriodicPacket( + subdp::DiagnosticsHkPeriodicParams(statusSet.getSid(), false, 5.0)); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(tmDataset.getSid(), false, 30.0)); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(lastResetStatusSet.getSid(), false, 30.0)); return RETURN_OK; } diff --git a/mission/devices/SusHandler.cpp b/mission/devices/SusHandler.cpp index 3cc10339..102613c7 100644 --- a/mission/devices/SusHandler.cpp +++ b/mission/devices/SusHandler.cpp @@ -202,7 +202,8 @@ ReturnValue_t SusHandler::initializeLocalDataPool(localpool::DataPool &localData LocalDataPoolManager &poolManager) { localDataPoolMap.emplace(SUS::TEMPERATURE_C, &tempC); localDataPoolMap.emplace(SUS::CHANNEL_VEC, &channelVec); - poolManager.subscribeForPeriodicPacket(dataset.getSid(), false, 5.0, true); + poolManager.subscribeForDiagPeriodicPacket( + subdp::DiagnosticsHkPeriodicParams(dataset.getSid(), false, 5.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/SyrlinksHkHandler.cpp b/mission/devices/SyrlinksHkHandler.cpp index 20d72995..67a015ec 100644 --- a/mission/devices/SyrlinksHkHandler.cpp +++ b/mission/devices/SyrlinksHkHandler.cpp @@ -621,9 +621,12 @@ ReturnValue_t SyrlinksHkHandler::initializeLocalDataPool(localpool::DataPool& lo localDataPoolMap.emplace(syrlinks::TEMP_BASEBAND_BOARD, new PoolEntry({0})); localDataPoolMap.emplace(syrlinks::TEMP_POWER_AMPLIFIER, new PoolEntry({0})); - poolManager.subscribeForPeriodicPacket(txDataset.getSid(), false, 5.0, true); - poolManager.subscribeForPeriodicPacket(rxDataset.getSid(), false, 5.0, true); - poolManager.subscribeForPeriodicPacket(temperatureSet.getSid(), false, 10.0, false); + poolManager.subscribeForDiagPeriodicPacket( + subdp::DiagnosticsHkPeriodicParams(txDataset.getSid(), false, 5.0)); + poolManager.subscribeForDiagPeriodicPacket( + subdp::DiagnosticsHkPeriodicParams(rxDataset.getSid(), false, 5.0)); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(temperatureSet.getSid(), false, 10.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/devices/Tmp1075Handler.cpp b/mission/devices/Tmp1075Handler.cpp index 8cc99ee6..995b4f81 100644 --- a/mission/devices/Tmp1075Handler.cpp +++ b/mission/devices/Tmp1075Handler.cpp @@ -123,6 +123,7 @@ uint32_t Tmp1075Handler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { ReturnValue_t Tmp1075Handler::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) { localDataPoolMap.emplace(TMP1075::TEMPERATURE_C_TMP1075, new PoolEntry({0.0})); - poolManager.subscribeForPeriodicPacket(dataset.getSid(), false, 30.0, false); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(dataset.getSid(), false, 30.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/tmtc/TmFunnel.cpp b/mission/tmtc/TmFunnel.cpp index 2eada527..30caa1c5 100644 --- a/mission/tmtc/TmFunnel.cpp +++ b/mission/tmtc/TmFunnel.cpp @@ -1,6 +1,7 @@ #include #include #include +#include #include #include @@ -9,8 +10,9 @@ object_id_t TmFunnel::downlinkDestination = objects::NO_OBJECT; object_id_t TmFunnel::storageDestination = objects::NO_OBJECT; -TmFunnel::TmFunnel(object_id_t objectId, uint32_t messageDepth, uint8_t reportReceptionVc) - : SystemObject(objectId), messageDepth(messageDepth), reportReceptionVc(reportReceptionVc) { +TmFunnel::TmFunnel(object_id_t objectId, CdsShortTimeStamper& timeReader, uint32_t messageDepth, + uint8_t reportReceptionVc) + : SystemObject(objectId), timeReader(timeReader), messageDepth(messageDepth), reportReceptionVc(reportReceptionVc) { auto mqArgs = MqArgs(objectId, static_cast(this)); tmQueue = QueueFactory::instance()->createMessageQueue( messageDepth, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs); @@ -49,11 +51,16 @@ ReturnValue_t TmFunnel::handlePacket(TmTcMessage* message) { if (result != HasReturnvaluesIF::RETURN_OK) { return result; } - TmPacketPusC packet(packetData); - packet.setPacketSequenceCount(this->sourceSequenceCount); - sourceSequenceCount++; - sourceSequenceCount = sourceSequenceCount % SpacePacketBase::LIMIT_SEQUENCE_COUNT; - packet.setErrorControl(); + + PusTmZeroCopyWriter packet(timeReader, packetData, size); + result = packet.parseDataWithoutCrcCheck(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + packet.setSequenceCount(sourceSequenceCount++); + sourceSequenceCount = sourceSequenceCount % ccsds::LIMIT_SEQUENCE_COUNT; + packet.updateErrorControl(); + result = tmQueue->sendToDefault(message); if (result != HasReturnvaluesIF::RETURN_OK) { @@ -107,7 +114,7 @@ ReturnValue_t TmFunnel::initialize() { AcceptsTelemetryIF* storageTarget = ObjectManager::instance()->get(storageDestination); if (storageTarget != nullptr) { - storageQueue->setDefaultDestination(storageTarget->getReportReceptionQueue()); + storageQueue->setDefaultDestination(storageTarget->getReportReceptionQueue(0)); } return SystemObject::initialize(); diff --git a/mission/tmtc/TmFunnel.h b/mission/tmtc/TmFunnel.h index f11dce63..98e581e9 100644 --- a/mission/tmtc/TmFunnel.h +++ b/mission/tmtc/TmFunnel.h @@ -4,6 +4,7 @@ #include #include #include +#include #include #include @@ -23,7 +24,7 @@ class TmFunnel : public AcceptsTelemetryIF, public ExecutableObjectIF, public Sy friend void(Factory::setStaticFrameworkObjectIds)(); public: - TmFunnel(object_id_t objectId, uint32_t messageDepth = 20, uint8_t reportReceptionVc = 0); + TmFunnel(object_id_t objectId, CdsShortTimeStamper& timeReader, uint32_t messageDepth = 20, uint8_t reportReceptionVc = 0); virtual ~TmFunnel(); virtual MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel = 0) override; @@ -35,6 +36,7 @@ class TmFunnel : public AcceptsTelemetryIF, public ExecutableObjectIF, public Sy static object_id_t storageDestination; private: + CdsShortTimeStamper& timeReader; uint32_t messageDepth = 0; uint8_t reportReceptionVc = 0; uint16_t sourceSequenceCount = 0; From 859ced185d185f30558d20f762ff7ea6631f2cb3 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 15 Aug 2022 12:23:54 +0200 Subject: [PATCH 02/58] start refactoring of PLOC SUPV packet defs --- .../PlocSupervisorDefinitions.h | 108 ++++++++++++++---- 1 file changed, 83 insertions(+), 25 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 462ee632..83c28dab 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -6,7 +6,7 @@ #include #include #include -#include +#include #include "linux/devices/devicedefinitions/SupvReturnValuesIF.h" @@ -274,10 +274,47 @@ static const uint32_t ERASE_MEMORY = 60000; static const uint32_t UPDATE_STATUS_REPORT = 70000; } // namespace recv_timeout +class SpacePacketBase { +public: + SpacePacketBase(SpacePacketCreator& creator, uint8_t* buf, size_t payloadLen, size_t maxSize) + : creator(creator), buf(buf), payloadLen(payloadLen), maxSize(maxSize) { + creator.setDataLen(payloadLen - 1); + creator.setPacketType(ccsds::PacketType::TC); + payloadStart = buf + ccsds::HEADER_LEN; + } + + ReturnValue_t checkPayloadLen() { + if(ccsds::HEADER_LEN + payloadLen > maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + return result::OK; + } + + ReturnValue_t serialize() { + size_t serLen = 0; + return creator.serializeBe(buf, serLen, maxSize); + } + + ReturnValue_t checkSizeAndSerialize() { + ReturnValue_t result = checkPayloadLen(); + if(result != result::OK) { + return result; + } + return serialize(); + } + +protected: + SpacePacketCreator& creator; + uint8_t* buf; + size_t payloadLen; + uint8_t* payloadStart; + size_t maxSize; +}; + /** * @brief This class creates a space packet containing only the header data and the CRC. */ -class ApidOnlyPacket : public SpacePacket { +class ApidOnlyPacket: public SpacePacketBase { public: /** * @brief Constructor @@ -286,20 +323,33 @@ class ApidOnlyPacket : public SpacePacket { * * @note Sequence count of empty packet is always 1. */ - ApidOnlyPacket(uint16_t apid) : SpacePacket(LENGTH_EMPTY_TC - 1, true, apid, 1) { calcCrc(); } + ApidOnlyPacket(uint16_t apid, SpacePacketCreator& creator, uint8_t* buf, size_t maxSize) + : SpacePacketBase(creator, buf, LENGTH_EMPTY_TC, maxSize) { + creator.setApid(apid); + + } + + ReturnValue_t buildPacket() { + ReturnValue_t result = checkSizeAndSerialize(); + if(result != result::OK) { + return result; + } + calcCrc(); + return result::OK; + } private: + /** * @brief CRC calculation which involves only the header in an empty packet */ void calcCrc() { /* Calculate crc */ - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, sizeof(CCSDSPrimaryHeader)); + uint16_t crc = CRC::crc16ccitt(buf, ccsds::HEADER_LEN); /* Add crc to packet data field of space packet */ size_t serializedSize = 0; - uint8_t* crcPos = this->localData.fields.buffer; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), + SerializeAdapter::serialize(&crc, &payloadStart, &serializedSize, sizeof(crc), SerializeIF::Endianness::BIG); } }; @@ -308,7 +358,7 @@ class ApidOnlyPacket : public SpacePacket { * @brief This class can be used to generate the space packet selecting the boot image of * of the MPSoC. */ -class MPSoCBootSelect : public SpacePacket { +class MPSoCBootSelect : public SpacePacketBase { public: static const uint8_t NVM0 = 0; static const uint8_t NVM1 = 1; @@ -323,13 +373,23 @@ class MPSoCBootSelect : public SpacePacket { * * @note Selection of partitions is currently not supported. */ - MPSoCBootSelect(uint8_t mem = 0, uint8_t bp0 = 0, uint8_t bp1 = 0, uint8_t bp2 = 0) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SEL_MPSOC_BOOT_IMAGE, DEFAULT_SEQUENCE_COUNT), - mem(mem), - bp0(bp0), - bp1(bp1), - bp2(bp2) { + MPSoCBootSelect(SpacePacketCreator& creator, uint8_t* buf, size_t maxSize) + : SpacePacketBase(creator, buf, DATA_FIELD_LENGTH - 1, maxSize) { + creator.setApid(APID_SEL_MPSOC_BOOT_IMAGE); + creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket(uint8_t mem_ = 0, uint8_t bp0_ = 0, uint8_t bp1_ = 0, uint8_t bp2_ = 0) { + mem = mem_; + bp0 = bp0_; + bp1 = bp1_; + bp2 = bp2_; + auto res = checkSizeAndSerialize(); + if(res != result::OK) { + return res; + } initPacket(); + return res; } private: @@ -348,18 +408,16 @@ class MPSoCBootSelect : public SpacePacket { uint8_t bp2 = 0; void initPacket() { - uint8_t* data_field_start = this->localData.fields.buffer; - std::memcpy(data_field_start + MEM_OFFSET, &mem, sizeof(mem)); - std::memcpy(data_field_start + BP0_OFFSET, &bp0, sizeof(bp0)); - std::memcpy(data_field_start + BP1_OFFSET, &bp1, sizeof(bp1)); - std::memcpy(data_field_start + BP2_OFFSET, &bp2, sizeof(bp2)); + std::memcpy(payloadStart + MEM_OFFSET, &mem, sizeof(mem)); + std::memcpy(payloadStart + BP0_OFFSET, &bp0, sizeof(bp0)); + std::memcpy(payloadStart + BP1_OFFSET, &bp1, sizeof(bp1)); + std::memcpy(payloadStart + BP2_OFFSET, &bp2, sizeof(bp2)); /* Calculate crc */ - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); + uint16_t crc = CRC::crc16ccitt(buf, ccsds::HEADER_LEN + DATA_FIELD_LENGTH - 2); /* Add crc to packet data field of space packet */ size_t serializedSize = 0; - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; + uint8_t* crcPos = payloadStart + CRC_OFFSET; SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), SerializeIF::Endianness::BIG); } @@ -369,7 +427,7 @@ class MPSoCBootSelect : public SpacePacket { * @brief This class creates the command to enable or disable the NVMs connected to the * supervisor. */ -class EnableNvms : public SpacePacket { +class EnableNvms : public SpacePacketCreator { public: /** * @brief Constructor @@ -412,7 +470,7 @@ class EnableNvms : public SpacePacket { /** * @brief This class generates the space packet to update the time of the PLOC supervisor. */ -class SetTimeRef : public SpacePacket { +class SetTimeRef : public SpacePacketCreator { public: SetTimeRef(Clock::TimeOfDay_t* time) : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_TIME_REF, DEFAULT_SEQUENCE_COUNT) { @@ -467,7 +525,7 @@ class SetTimeRef : public SpacePacket { /** * @brief This class can be used to generate the set boot timout command. */ -class SetBootTimeout : public SpacePacket { +class SetBootTimeout : public SpacePacketCreator { public: /** * @brief Constructor @@ -503,7 +561,7 @@ class SetBootTimeout : public SpacePacket { /** * @brief This class can be used to generate the space packet to set the maximum boot tries. */ -class SetRestartTries : public SpacePacket { +class SetRestartTries : public SpacePacketCreator { public: /** * @brief Constructor From f071b7eba462086e673634538a46142c0b016e13 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 15 Aug 2022 13:03:23 +0200 Subject: [PATCH 03/58] thats a lot of rewriting.. --- .../PlocSupervisorDefinitions.h | 512 +++++++++--------- 1 file changed, 265 insertions(+), 247 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 83c28dab..56ea8d4a 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -256,6 +256,7 @@ 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; @@ -274,41 +275,70 @@ static const uint32_t ERASE_MEMORY = 60000; static const uint32_t UPDATE_STATUS_REPORT = 70000; } // namespace recv_timeout +struct SpBaseParams { + SpBaseParams(SpacePacketCreator& creator, uint8_t* buf, size_t maxSize): + creator(creator), buf(buf), maxSize(maxSize) {} + + + void setPayloadLen(size_t payloadLen_) { + payloadLen = payloadLen_; + } + + SpacePacketCreator& creator; + uint8_t* buf; + size_t maxSize; + size_t payloadLen = 0; + +}; + class SpacePacketBase { public: - SpacePacketBase(SpacePacketCreator& creator, uint8_t* buf, size_t payloadLen, size_t maxSize) - : creator(creator), buf(buf), payloadLen(payloadLen), maxSize(maxSize) { - creator.setDataLen(payloadLen - 1); - creator.setPacketType(ccsds::PacketType::TC); - payloadStart = buf + ccsds::HEADER_LEN; + SpacePacketBase(SpBaseParams params) + : spParams(params) { + payloadStart = spParams.buf + ccsds::HEADER_LEN; + updateFields(); + } + + void updateFields() { + spParams.creator.setDataLen(spParams.payloadLen - 1); + spParams.creator.setPacketType(ccsds::PacketType::TC); } ReturnValue_t checkPayloadLen() { - if(ccsds::HEADER_LEN + payloadLen > maxSize) { + if(ccsds::HEADER_LEN + spParams.payloadLen > spParams.maxSize) { return SerializeIF::BUFFER_TOO_SHORT; } + return result::OK; } - ReturnValue_t serialize() { + ReturnValue_t serializeHeader() { + updateFields(); size_t serLen = 0; - return creator.serializeBe(buf, serLen, maxSize); + return spParams.creator.serializeBe(spParams.buf, serLen, spParams.maxSize); } - ReturnValue_t checkSizeAndSerialize() { + ReturnValue_t checkSizeAndSerializeHeader() { ReturnValue_t result = checkPayloadLen(); if(result != result::OK) { return result; } - return serialize(); + return serializeHeader(); + } + + ReturnValue_t calcCrc() { + /* Calculate crc */ + uint16_t crc = CRC::crc16ccitt(spParams.buf, ccsds::HEADER_LEN + spParams.payloadLen - 2); + + /* Add crc to packet data field of space packet */ + size_t serializedSize = 0; + return SerializeAdapter::serialize(&crc, &payloadStart, &serializedSize, sizeof(crc), + SerializeIF::Endianness::BIG); } protected: - SpacePacketCreator& creator; - uint8_t* buf; - size_t payloadLen; + SpBaseParams spParams; uint8_t* payloadStart; - size_t maxSize; }; /** @@ -323,35 +353,21 @@ class ApidOnlyPacket: public SpacePacketBase { * * @note Sequence count of empty packet is always 1. */ - ApidOnlyPacket(uint16_t apid, SpacePacketCreator& creator, uint8_t* buf, size_t maxSize) - : SpacePacketBase(creator, buf, LENGTH_EMPTY_TC, maxSize) { - creator.setApid(apid); - + ApidOnlyPacket(SpBaseParams params, uint16_t apid) + : SpacePacketBase(params) { + spParams.setPayloadLen(LENGTH_EMPTY_TC); + spParams.creator.setApid(apid); } ReturnValue_t buildPacket() { - ReturnValue_t result = checkSizeAndSerialize(); - if(result != result::OK) { - return result; + auto res = checkSizeAndSerializeHeader(); + if(res != result::OK) { + return res; } - calcCrc(); - return result::OK; + return calcCrc(); } private: - - /** - * @brief CRC calculation which involves only the header in an empty packet - */ - void calcCrc() { - /* Calculate crc */ - uint16_t crc = CRC::crc16ccitt(buf, ccsds::HEADER_LEN); - - /* Add crc to packet data field of space packet */ - size_t serializedSize = 0; - SerializeAdapter::serialize(&crc, &payloadStart, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } }; /** @@ -373,28 +389,24 @@ class MPSoCBootSelect : public SpacePacketBase { * * @note Selection of partitions is currently not supported. */ - MPSoCBootSelect(SpacePacketCreator& creator, uint8_t* buf, size_t maxSize) - : SpacePacketBase(creator, buf, DATA_FIELD_LENGTH - 1, maxSize) { - creator.setApid(APID_SEL_MPSOC_BOOT_IMAGE); - creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + MPSoCBootSelect(SpBaseParams params) + : SpacePacketBase(params) { + spParams.setPayloadLen(DATA_FIELD_LENGTH); + spParams.creator.setApid(APID_SEL_MPSOC_BOOT_IMAGE); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } - ReturnValue_t buildPacket(uint8_t mem_ = 0, uint8_t bp0_ = 0, uint8_t bp1_ = 0, uint8_t bp2_ = 0) { - mem = mem_; - bp0 = bp0_; - bp1 = bp1_; - bp2 = bp2_; - auto res = checkSizeAndSerialize(); + ReturnValue_t buildPacket(uint8_t mem = 0, uint8_t bp0 = 0, uint8_t bp1 = 0, uint8_t bp2 = 0) { + auto res = checkSizeAndSerializeHeader(); if(res != result::OK) { return res; } - initPacket(); - return res; + initPacket(mem, bp0, bp1, bp2); + return calcCrc(); } private: static const uint16_t DATA_FIELD_LENGTH = 6; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; static const uint8_t MEM_OFFSET = 0; static const uint8_t BP0_OFFSET = 1; @@ -402,24 +414,11 @@ class MPSoCBootSelect : public SpacePacketBase { static const uint8_t BP2_OFFSET = 3; static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; - uint8_t mem = 0; - uint8_t bp0 = 0; - uint8_t bp1 = 0; - uint8_t bp2 = 0; - - void initPacket() { + void initPacket(uint8_t mem = 0, uint8_t bp0 = 0, uint8_t bp1 = 0, uint8_t bp2 = 0) { std::memcpy(payloadStart + MEM_OFFSET, &mem, sizeof(mem)); std::memcpy(payloadStart + BP0_OFFSET, &bp0, sizeof(bp0)); std::memcpy(payloadStart + BP1_OFFSET, &bp1, sizeof(bp1)); std::memcpy(payloadStart + BP2_OFFSET, &bp2, sizeof(bp2)); - /* Calculate crc */ - uint16_t crc = CRC::crc16ccitt(buf, ccsds::HEADER_LEN + DATA_FIELD_LENGTH - 2); - - /* Add crc to packet data field of space packet */ - size_t serializedSize = 0; - uint8_t* crcPos = payloadStart + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); } }; @@ -427,7 +426,7 @@ class MPSoCBootSelect : public SpacePacketBase { * @brief This class creates the command to enable or disable the NVMs connected to the * supervisor. */ -class EnableNvms : public SpacePacketCreator { +class EnableNvms : public SpacePacketBase { public: /** * @brief Constructor @@ -437,55 +436,63 @@ class EnableNvms : public SpacePacketCreator { * @param bp1 Partition pin 1 * @param bp2 Partition pin 2 */ - EnableNvms(uint8_t nvm01, uint8_t nvm3) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_ENABLE_NVMS, DEFAULT_SEQUENCE_COUNT), - nvm01(nvm01), - nvm3(nvm3) { - initPacket(); + EnableNvms(SpBaseParams params) + : SpacePacketBase(params) { + spParams.setPayloadLen(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 != result::OK) { + return res; + } + initPacket(nvm01, nvm3); + return calcCrc(); + } + + private: - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; static const uint8_t DATA_FIELD_LENGTH = 4; static const uint8_t CRC_OFFSET = 2; - uint8_t nvm01 = 0; - uint8_t nvm3 = 0; - void initPacket() { - *(this->localData.fields.buffer) = nvm01; - *(this->localData.fields.buffer + 1) = nvm3; - - /* Calculate crc */ - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - - /* Add crc to packet data field of space packet */ - size_t serializedSize = 0; - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); + 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 SpacePacketCreator { +class SetTimeRef : public SpacePacketBase { public: - SetTimeRef(Clock::TimeOfDay_t* time) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_TIME_REF, DEFAULT_SEQUENCE_COUNT) { + SetTimeRef(SpBaseParams params) + : SpacePacketBase(params) { + spParams.setPayloadLen(DATA_FIELD_LENGTH); + spParams.creator.setApid(APID_SET_TIME_REF); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + + } + + ReturnValue_t buildPacket(Clock::TimeOfDay_t* time) { + auto res = checkSizeAndSerializeHeader(); + if(res != result::OK) { + return res; + } initPacket(time); + return calcCrc(); } private: static const uint16_t DATA_FIELD_LENGTH = 10; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; static const uint16_t SYNC = 0x8000; void initPacket(Clock::TimeOfDay_t* time) { size_t serializedSize = 0; - uint8_t* dataFieldPtr = this->localData.fields.buffer; + uint8_t* dataFieldPtr = payloadStart; uint16_t milliseconds = static_cast(time->usecond / 1000) | SYNC; SerializeAdapter::serialize(&milliseconds, &dataFieldPtr, &serializedSize, sizeof(milliseconds), SerializeIF::Endianness::BIG); @@ -513,65 +520,72 @@ class SetTimeRef : public SpacePacketCreator { serializedSize = 0; SerializeAdapter::serialize(&year, &dataFieldPtr, &serializedSize, sizeof(time->year), SerializeIF::Endianness::BIG); - serializedSize = 0; - /* Calculate crc */ - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - SerializeAdapter::serialize(&crc, &dataFieldPtr, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); } }; /** * @brief This class can be used to generate the set boot timout command. */ -class SetBootTimeout : public SpacePacketCreator { +class SetBootTimeout : public SpacePacketBase { public: /** * @brief Constructor * * @param timeout The boot timeout in milliseconds. */ - SetBootTimeout(uint32_t timeout) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_BOOT_TIMEOUT, 1), timeout(timeout) { - initPacket(); + SetBootTimeout(SpBaseParams params) + : SpacePacketBase(params) { + spParams.setPayloadLen(DATA_FIELD_LENGTH); + spParams.creator.setApid(APID_SET_BOOT_TIMEOUT); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + + } + + ReturnValue_t buildPacket(uint32_t timeout) { + auto res = checkSizeAndSerializeHeader(); + if(res != result::OK) { + return res; + } + initPacket(timeout); + return calcCrc(); } private: - uint32_t timeout = 0; - /** boot timeout value (uint32_t) and crc (uint16_t) */ static const uint16_t DATA_FIELD_LENGTH = 6; - void initPacket() { + void initPacket(uint32_t timeout) { size_t serializedSize = 0; - uint8_t* dataFieldPtr = this->localData.fields.buffer; + uint8_t* dataFieldPtr = payloadStart; SerializeAdapter::serialize(&timeout, &dataFieldPtr, &serializedSize, sizeof(timeout), SerializeIF::Endianness::BIG); - /* Calculate crc */ - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - /* Add crc to packet data field of space packet */ - serializedSize = 0; - SerializeAdapter::serialize(&crc, &dataFieldPtr, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); } }; /** * @brief This class can be used to generate the space packet to set the maximum boot tries. */ -class SetRestartTries : public SpacePacketCreator { +class SetRestartTries : public SpacePacketBase { public: /** * @brief Constructor * * @param restartTries Maximum restart tries to set. */ - SetRestartTries(uint8_t restartTries) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_MAX_RESTART_TRIES, 1), - restartTries(restartTries) { - initPacket(); + SetRestartTries(SpBaseParams params) + : SpacePacketBase(params) { + spParams.setPayloadLen(DATA_FIELD_LENGTH); + spParams.creator.setApid(APID_SET_MAX_RESTART_TRIES); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket(uint8_t restartTries) { + auto res = checkSizeAndSerializeHeader(); + if(res != result::OK) { + return res; + } + initPacket(restartTries); + return calcCrc(); } private: @@ -580,15 +594,8 @@ class SetRestartTries : public SpacePacketCreator { /** Restart tries value (uint8_t) and crc (uint16_t) */ static const uint16_t DATA_FIELD_LENGTH = 3; - void initPacket() { - uint8_t* dataFieldPtr = this->localData.fields.buffer; - *dataFieldPtr = restartTries; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - size_t serializedSize = 0; - uint8_t* crcPtr = dataFieldPtr + 1; - SerializeAdapter::serialize(&crc, &crcPtr, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); + void initPacket(uint8_t restartTries) { + payloadStart[0] = restartTries; } }; @@ -597,30 +604,33 @@ class SetRestartTries : public SpacePacketCreator { * of housekeeping data. Normally, this will be disabled by default. However, adding this * command can be useful for debugging. */ -class DisablePeriodicHkTransmission : public SpacePacket { +class DisablePeriodicHkTransmission : public SpacePacketBase { public: /** * @brief Constructor */ - DisablePeriodicHkTransmission() : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_DISABLE_HK, 1) { + DisablePeriodicHkTransmission(SpBaseParams params): SpacePacketBase(params) { + spParams.setPayloadLen(DATA_FIELD_LENGTH); + spParams.creator.setApid(APID_DISABLE_HK); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket() { + auto res = checkSizeAndSerializeHeader(); + if(res != result::OK) { + return res; + } initPacket(); + return calcCrc(); } private: - uint8_t disableHk = 0; /** Restart tries value (uint8_t) and crc (uint16_t) */ static const uint16_t DATA_FIELD_LENGTH = 3; void initPacket() { - uint8_t* dataFieldPtr = this->localData.fields.buffer; - *dataFieldPtr = disableHk; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - size_t serializedSize = 0; - uint8_t* crcPtr = dataFieldPtr + 1; - SerializeAdapter::serialize(&crc, &crcPtr, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); + payloadStart[0] = false; } }; @@ -629,7 +639,7 @@ class DisablePeriodicHkTransmission : public SpacePacket { * * @details There are 7 different latchup alerts. */ -class LatchupAlert : public SpacePacket { +class LatchupAlert : public SpacePacketBase { public: /** * @brief Constructor @@ -638,40 +648,40 @@ class LatchupAlert : public SpacePacket { * @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(bool state, uint8_t latchupId) - : SpacePacket(DATA_FIELD_LENGTH - 1, true), latchupId(latchupId) { + LatchupAlert(SpBaseParams params) + : SpacePacketBase(params) { + spParams.setPayloadLen(DATA_FIELD_LENGTH); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + + } + + ReturnValue_t buildPacket(bool state, uint8_t latchupId) { if (state) { - this->setAPID(APID_ENABLE_LATCHUP_ALERT); + spParams.creator.setApid(APID_ENABLE_LATCHUP_ALERT); } else { - this->setAPID(APID_DISABLE_LATCHUP_ALERT); + spParams.creator.setApid(APID_DISABLE_LATCHUP_ALERT); } - this->setPacketSequenceCount(DEFAULT_SEQUENCE_COUNT); - initPacket(); + auto res = checkSizeAndSerializeHeader(); + if(res != result::OK) { + return res; + } + initPacket(latchupId); + return calcCrc(); } 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 latchupId = 0; - void initPacket() { - size_t serializedSize = 0; - uint8_t* data_field_ptr = this->localData.fields.buffer; - SerializeAdapter::serialize(&latchupId, &data_field_ptr, &serializedSize, - sizeof(latchupId), SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); + void initPacket(uint8_t latchupId) { + payloadStart[0] = latchupId; } }; -class SetAlertlimit : public SpacePacket { +class SetAlertlimit : public SpacePacketBase { public: /** * @brief Constructor @@ -680,74 +690,78 @@ class SetAlertlimit : public SpacePacket { * 3 - 3.3V, 4 - NVM_4XO, 5 - MISSION, 6 - SAFECOTS) * @param dutycycle */ - SetAlertlimit(uint8_t latchupId, uint32_t dutycycle) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ALERT_LIMIT, DEFAULT_SEQUENCE_COUNT), - latchupId(latchupId), - dutycycle(dutycycle) { - initPacket(); + SetAlertlimit(SpBaseParams params) + : SpacePacketBase(params) { + spParams.setPayloadLen(DATA_FIELD_LENGTH); + spParams.creator.setApid(APID_SET_ALERT_LIMIT); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + ReturnValue_t buildPacket(uint8_t latchupId, uint32_t dutycycle) { + auto res = checkSizeAndSerializeHeader(); + if(res != result::OK) { + return res; + } + res = initPacket(latchupId, dutycycle); + if(res != result::OK) { + return res; + } + return calcCrc(); + } + private: static const uint16_t DATA_FIELD_LENGTH = 7; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; uint8_t latchupId = 0; uint32_t dutycycle = 0; - void initPacket() { - size_t serializedSize = 0; - uint8_t* dataFieldPtr = this->localData.fields.buffer; - SerializeAdapter::serialize(&latchupId, &dataFieldPtr, &serializedSize, - sizeof(latchupId), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&dutycycle, &dataFieldPtr, &serializedSize, + ReturnValue_t initPacket(uint8_t latchupId, uint32_t dutycycle) { + payloadStart[0] = latchupId; + size_t serLen = 0; + return SerializeAdapter::serialize(&dutycycle, payloadStart + 1, &serLen, sizeof(dutycycle), SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); } }; /** * @brief This class packages the space packet to enable or disable ADC channels. */ -class SetAdcEnabledChannels : public SpacePacket { +class SetAdcEnabledChannels : public SpacePacketBase { public: /** * @brief Constructor * * @param ch Defines channels to be enabled or disabled. */ - SetAdcEnabledChannels(uint16_t ch) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ADC_ENABLED_CHANNELS, - DEFAULT_SEQUENCE_COUNT), - ch(ch) { - initPacket(); + SetAdcEnabledChannels(SpBaseParams params) + : SpacePacketBase(params) { + spParams.setPayloadLen(DATA_FIELD_LENGTH); + spParams.creator.setApid(APID_SET_ADC_ENABLED_CHANNELS); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket(uint16_t ch) { + auto res = checkSizeAndSerializeHeader(); + if(res != result::OK) { + return res; + } + res = initPacket(ch); + if(res != result::OK) { + return res; + } + return calcCrc(); } 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; - uint16_t ch = 0; - - void initPacket() { + void initPacket(uint16_t ch) { size_t serializedSize = 0; - uint8_t* dataFieldPtr = this->localData.fields.buffer; - SerializeAdapter::serialize(&ch, &dataFieldPtr, &serializedSize, sizeof(ch), - SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), + SerializeAdapter::serialize(&ch, &payloadStart, &serializedSize, sizeof(ch), SerializeIF::Endianness::BIG); } }; @@ -756,7 +770,7 @@ class SetAdcEnabledChannels : public SpacePacket { * @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 SpacePacket { +class SetAdcWindowAndStride : public SpacePacketBase { public: /** * @brief Constructor @@ -764,94 +778,107 @@ class SetAdcWindowAndStride : public SpacePacket { * @param windowSize * @param stridingStepSize */ - SetAdcWindowAndStride(uint16_t windowSize, uint16_t stridingStepSize) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ADC_WINDOW_AND_STRIDE, - DEFAULT_SEQUENCE_COUNT), - windowSize(windowSize), - stridingStepSize(stridingStepSize) { - initPacket(); + SetAdcWindowAndStride(SpBaseParams params): SpacePacketBase(params) { + spParams.setPayloadLen(DATA_FIELD_LENGTH); + spParams.creator.setApid(APID_SET_ADC_WINDOW_AND_STRIDE); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } + ReturnValue_t buildPacket(uint16_t windowSize, uint16_t stridingStepSize) { + auto res = checkSizeAndSerializeHeader(); + if(res != result::OK) { + return res; + } + res = initPacket(windowSize, stridingStepSize); + if(res != result::OK) { + return res; + } + return calcCrc(); + } + 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; - uint16_t windowSize = 0; - uint16_t stridingStepSize = 0; - void initPacket() { + void initPacket(uint16_t windowSize, uint16_t stridingStepSize) { size_t serializedSize = 0; - uint8_t* dataFieldPtr = this->localData.fields.buffer; - SerializeAdapter::serialize(&windowSize, &dataFieldPtr, &serializedSize, + uint8_t* data = payloadStart; + SerializeAdapter::serialize(&windowSize, &data, &serializedSize, sizeof(windowSize), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&stridingStepSize, &dataFieldPtr, &serializedSize, + SerializeAdapter::serialize(&stridingStepSize, &data, &serializedSize, sizeof(stridingStepSize), SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); } }; /** * @brief This class packages the space packet to set the ADC trigger threshold. */ -class SetAdcThreshold : public SpacePacket { +class SetAdcThreshold : public SpacePacketBase { public: /** * @brief Constructor * * @param threshold */ - SetAdcThreshold(uint32_t threshold) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_ADC_THRESHOLD, DEFAULT_SEQUENCE_COUNT), - threshold(threshold) { - initPacket(); + SetAdcThreshold(SpBaseParams params): SpacePacketBase(params) { + spParams.setPayloadLen(DATA_FIELD_LENGTH); + spParams.creator.setApid(APID_SET_ADC_THRESHOLD); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } + ReturnValue_t buildPacket(uint32_t threshold) { + auto res = checkSizeAndSerializeHeader(); + if(res != result::OK) { + return res; + } + res = initPacket(threshold); + if(res != result::OK) { + return res; + } + return calcCrc(); + } 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; - uint32_t threshold = 0; - - void initPacket() { + void initPacket(uint32_t threshold) { size_t serializedSize = 0; - uint8_t* dataFieldPtr = this->localData.fields.buffer; - SerializeAdapter::serialize(&threshold, &dataFieldPtr, &serializedSize, + SerializeAdapter::serialize(&threshold, payloadStart, &serializedSize, sizeof(threshold), SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); } }; /** * @brief This class packages the space packet to run auto EM tests. */ -class RunAutoEmTests : public SpacePacket { +class RunAutoEmTests : public SpacePacketBase { public: /** * @brief Constructor * * @param test 1 - complete EM test, 2 - Short test (only memory readback NVM0,1,3) */ - RunAutoEmTests(uint8_t test) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_RUN_AUTO_EM_TESTS, DEFAULT_SEQUENCE_COUNT), - test(test) { - initPacket(); + RunAutoEmTests(SpBaseParams params) : SpacePacketBase(params) { + spParams.setPayloadLen(DATA_FIELD_LENGTH); + spParams.creator.setApid(APID_RUN_AUTO_EM_TESTS); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } + ReturnValue_t buildPacket(uint8_t test) { + auto res = checkSizeAndSerializeHeader(); + if(res != result::OK) { + return res; + } + res = initPacket(test); + if(res != result::OK) { + return res; + } + return calcCrc(); + } private: static const uint16_t DATA_FIELD_LENGTH = 3; static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; @@ -860,17 +887,8 @@ class RunAutoEmTests : public SpacePacket { uint8_t test = 0; - void initPacket() { - size_t serializedSize = 0; - uint8_t* dataFieldPtr = this->localData.fields.buffer; - SerializeAdapter::serialize(&test, &dataFieldPtr, &serializedSize, sizeof(test), - SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); + void initPacket(uint8_t test) { + payloadStart[0] = test; } }; From 0c371623c6f1cb265b40cd26d59eb4796b8a882e Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 15 Aug 2022 17:25:16 +0200 Subject: [PATCH 04/58] change PLOC/MPSOC code to using new SP code --- common/config/commonConfig.cpp | 4 +- fsfw | 2 +- .../devicedefinitions/PlocMPSoCDefinitions.h | 269 +++--- .../PlocSupervisorDefinitions.h | 797 ++++++++---------- linux/devices/ploc/PlocMPSoCHandler.cpp | 104 ++- linux/devices/ploc/PlocMPSoCHandler.h | 14 +- linux/devices/ploc/PlocMemoryDumper.h | 1 - linux/devices/ploc/PlocSupervisorHandler.cpp | 291 +++++-- linux/devices/ploc/PlocSupervisorHandler.h | 26 +- linux/devices/ploc/PlocSupvHelper.cpp | 60 +- linux/devices/ploc/PlocSupvHelper.h | 7 +- mission/controller/AcsController.cpp | 20 +- mission/controller/AcsController.h | 18 +- .../AcsCtrlDefinitions.h | 18 +- mission/core/GenericFactory.cpp | 11 +- mission/devices/IMTQHandler.cpp | 6 +- mission/devices/PCDUHandler.h | 3 +- mission/devices/devicedefinitions/SpBase.h | 83 ++ mission/tmtc/TmFunnel.cpp | 10 +- mission/tmtc/TmFunnel.h | 3 +- 20 files changed, 946 insertions(+), 801 deletions(-) create mode 100644 mission/devices/devicedefinitions/SpBase.h diff --git a/common/config/commonConfig.cpp b/common/config/commonConfig.cpp index 0fd78a61..08b7439f 100644 --- a/common/config/commonConfig.cpp +++ b/common/config/commonConfig.cpp @@ -1,8 +1,8 @@ #include "commonConfig.h" -#include "fsfw/tmtcpacket/SpacePacket.h" +#include "fsfw/tmtcpacket/ccsds/defs.h" #include "tmtc/apid.h" const fsfw::Version common::OBSW_VERSION{OBSW_VERSION_MAJOR, OBSW_VERSION_MINOR, OBSW_VERSION_REVISION, OBSW_VERSION_CST_GIT_SHA1}; -const uint16_t common::PUS_PACKET_ID = spacepacket::getTcSpacePacketIdFromApid(apid::EIVE_OBSW); +const uint16_t common::PUS_PACKET_ID = ccsds::getTcSpacePacketIdFromApid(apid::EIVE_OBSW); diff --git a/fsfw b/fsfw index 007f958a..4d82d0e4 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 007f958a0b787a572bf1bd98b348c3a632799bf7 +Subproject commit 4d82d0e4c15091aceafc8279790517702d5941f4 diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index d64bb863..5ec211b2 100644 --- a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h +++ b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h @@ -6,7 +6,7 @@ #include "eive/definitions.h" #include "fsfw/globalfunctions/CRC.h" #include "fsfw/serialize/SerializeAdapter.h" -#include "fsfw/tmtcpacket/SpacePacket.h" +#include "mission/devices/devicedefinitions/SpBase.h" namespace mpsoc { @@ -73,6 +73,8 @@ static const char NULL_TERMINATOR = '\0'; static const uint8_t MIN_SPACE_PACKET_LENGTH = 7; static const uint8_t SPACE_PACKET_HEADER_SIZE = 6; +static constexpr size_t CRC_SIZE = 2; + /** * The size of payload data which will be forwarded to the requesting object. e.g. PUS Service * 8. @@ -88,8 +90,12 @@ static const size_t MAX_FILENAME_SIZE = 256; static const uint16_t LENGTH_TC_MEM_WRITE = 12; static const uint16_t LENGTH_TC_MEM_READ = 8; -static const size_t MAX_REPLY_SIZE = SpacePacket::PACKET_MAX_SIZE * 3; -static const size_t MAX_COMMAND_SIZE = SpacePacket::PACKET_MAX_SIZE; +/** + * TODO: Might be a good idea to document where this is coming from + */ +static constexpr size_t SP_MAX_SIZE = 1024; +static const size_t MAX_REPLY_SIZE = SP_MAX_SIZE * 3; +static const size_t MAX_COMMAND_SIZE = SP_MAX_SIZE; static const size_t MAX_DATA_SIZE = 1016; /** @@ -130,8 +136,10 @@ static const uint16_t RESERVED_4 = 0x5F4; /** * @brief Abstract base class for TC space packet of MPSoC. */ -class TcBase : public SpacePacket, public MPSoCReturnValuesIF { +class TcBase : public SpacePacketBase, public MPSoCReturnValuesIF { public: + virtual ~TcBase() = default; + // Initial length field of space packet. Will always be updated when packet is created. static const uint16_t INIT_LENGTH = 1; @@ -141,8 +149,12 @@ class TcBase : public SpacePacket, public MPSoCReturnValuesIF { * @param sequenceCount Sequence count of space packet which will be incremented with each * sent and received packets. */ - TcBase(uint16_t apid, uint16_t sequenceCount) - : SpacePacket(INIT_LENGTH, true, apid, sequenceCount) {} + TcBase(SpBaseParams params, uint16_t apid, uint16_t sequenceCount) + : SpacePacketBase(params, apid, sequenceCount) { + spParams.setDataFieldLen(INIT_LENGTH); + } + + ReturnValue_t buildPacket() { return buildPacket(nullptr, 0); } /** * @brief Function to initialize the space packet @@ -152,17 +164,22 @@ class TcBase : public SpacePacket, public MPSoCReturnValuesIF { * * @return RETURN_OK if packet creation was successful, otherwise error return value */ - virtual ReturnValue_t createPacket(const uint8_t* commandData, size_t commandDataLen) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - result = initPacket(commandData, commandDataLen); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; + ReturnValue_t buildPacket(const uint8_t* commandData, size_t commandDataLen) { + payloadStart = spParams.buf + ccsds::HEADER_LEN; + ReturnValue_t res; + if (commandData != nullptr and commandDataLen > 0) { + res = initPacket(commandData, commandDataLen); + if (res != result::OK) { + return res; + } } - result = addCrc(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; + + updateFields(); + res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; } - return result; + return calcCrc(); } protected: @@ -175,23 +192,6 @@ class TcBase : public SpacePacket, public MPSoCReturnValuesIF { virtual ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) { return HasReturnvaluesIF::RETURN_OK; } - - /** - * @brief Calculates and adds the CRC - */ - ReturnValue_t addCrc() { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - size_t serializedSize = 0; - uint32_t full_size = getFullSize(); - uint16_t crc = CRC::crc16ccitt(getWholeData(), full_size - CRC_SIZE); - result = SerializeAdapter::serialize( - &crc, this->localData.byteStream + full_size - CRC_SIZE, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::debug << "TcBase::addCrc: Failed to serialize crc field" << std::endl; - } - return result; - } }; /** @@ -224,22 +224,22 @@ class TcMemRead : public TcBase { /** * @brief Constructor */ - TcMemRead(uint16_t sequenceCount) : TcBase(apid::TC_MEM_READ, sequenceCount) { - this->setPacketDataLength(PACKET_LENGTH); + TcMemRead(SpBaseParams params, uint16_t sequenceCount) + : TcBase(params, apid::TC_MEM_READ, sequenceCount) { + spParams.setPayloadLen(COMMAND_LENGTH); } uint16_t getMemLen() const { return memLen; } protected: - ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) { + ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; result = lengthCheck(commandDataLen); if (result != HasReturnvaluesIF::RETURN_OK) { return result; } - std::memcpy(this->localData.fields.buffer, commandData, MEM_ADDRESS_SIZE); - std::memcpy(this->localData.fields.buffer + MEM_ADDRESS_SIZE, commandData + MEM_ADDRESS_SIZE, - MEM_LEN_SIZE); + std::memcpy(payloadStart, commandData, MEM_ADDRESS_SIZE); + std::memcpy(payloadStart + MEM_ADDRESS_SIZE, commandData + MEM_ADDRESS_SIZE, MEM_LEN_SIZE); size_t size = sizeof(memLen); const uint8_t* memLenPtr = commandData + MEM_ADDRESS_SIZE; result = @@ -247,6 +247,7 @@ class TcMemRead : public TcBase { if (result != HasReturnvaluesIF::RETURN_OK) { return result; } + spParams.setPayloadLen(MEM_ADDRESS_SIZE + MEM_LEN_SIZE); return result; } @@ -275,19 +276,21 @@ class TcMemWrite : public TcBase { /** * @brief Constructor */ - TcMemWrite(uint16_t sequenceCount) : TcBase(apid::TC_MEM_WRITE, sequenceCount) {} + TcMemWrite(SpBaseParams params, uint16_t sequenceCount) + : TcBase(params, apid::TC_MEM_WRITE, sequenceCount) {} protected: - ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) { + // TODO: Confusing, recheck.. + ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; result = lengthCheck(commandDataLen); if (result != HasReturnvaluesIF::RETURN_OK) { return result; } - std::memcpy(this->localData.fields.buffer, commandData, commandDataLen); + std::memcpy(payloadStart, commandData, commandDataLen); uint16_t memLen = *(commandData + MEM_ADDRESS_SIZE) << 8 | *(commandData + MEM_ADDRESS_SIZE + 1); - this->setPacketDataLength(memLen * 4 + FIX_LENGTH - 1); + spParams.setPayloadLen(FIX_LENGTH + memLen * 4); return result; } @@ -309,9 +312,10 @@ class TcMemWrite : public TcBase { /** * @brief Class to help creation of flash fopen command. */ -class FlashFopen : public TcBase { +class FlashFopen : public SpacePacketBase { public: - FlashFopen(uint16_t sequenceCount) : TcBase(apid::TC_FLASHFOPEN, sequenceCount) {} + FlashFopen(SpBaseParams params, uint16_t sequenceCount) + : SpacePacketBase(params, apid::TC_FLASHFOPEN, sequenceCount) {} static const char APPEND = 'a'; static const char WRITE = 'w'; @@ -321,17 +325,12 @@ class FlashFopen : public TcBase { accessMode = accessMode_; ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; size_t nameSize = filename.size(); - std::memcpy(this->getPacketData(), filename.c_str(), nameSize); - *(this->getPacketData() + nameSize) = NULL_TERMINATOR; - std::memcpy(this->getPacketData() + nameSize + sizeof(NULL_TERMINATOR), &accessMode, - sizeof(accessMode)); - this->setPacketDataLength(nameSize + sizeof(NULL_TERMINATOR) + sizeof(accessMode) + CRC_SIZE - - 1); - result = addCrc(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return result; + std::memcpy(payloadStart, filename.c_str(), nameSize); + *(spParams.buf + nameSize) = NULL_TERMINATOR; + std::memcpy(payloadStart + nameSize + sizeof(NULL_TERMINATOR), &accessMode, sizeof(accessMode)); + spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR) + sizeof(accessMode)); + updateFields(); + return calcCrc(); } private: @@ -343,28 +342,25 @@ class FlashFopen : public TcBase { */ class FlashFclose : public TcBase { public: - FlashFclose(uint16_t sequenceCount) : TcBase(apid::TC_FLASHFCLOSE, sequenceCount) {} + FlashFclose(SpBaseParams params, uint16_t sequenceCount) + : TcBase(params, apid::TC_FLASHFCLOSE, sequenceCount) {} ReturnValue_t createPacket(std::string filename) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; size_t nameSize = filename.size(); - std::memcpy(this->getPacketData(), filename.c_str(), nameSize); - *(this->getPacketData() + nameSize) = NULL_TERMINATOR; - this->setPacketDataLength(nameSize + sizeof(NULL_TERMINATOR) + CRC_SIZE - 1); - result = addCrc(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - return result; + std::memcpy(payloadStart, filename.c_str(), nameSize); + *(payloadStart + nameSize) = NULL_TERMINATOR; + spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR)); + return calcCrc(); } }; /** * @brief Class to build flash write space packet. */ -class TcFlashWrite : public TcBase { +class TcFlashWrite : public SpacePacketBase { public: - TcFlashWrite(uint16_t sequenceCount) : TcBase(apid::TC_FLASHWRITE, sequenceCount) {} + TcFlashWrite(SpBaseParams params, uint16_t sequenceCount) + : SpacePacketBase(params, apid::TC_FLASHWRITE, sequenceCount) {} ReturnValue_t createPacket(const uint8_t* writeData, uint32_t writeLen_) { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; @@ -374,19 +370,19 @@ class TcFlashWrite : public TcBase { return HasReturnvaluesIF::RETURN_FAILED; } size_t serializedSize = 0; - result = - SerializeAdapter::serialize(&writeLen, this->getPacketData(), &serializedSize, - sizeof(writeLen), SerializeIF::Endianness::BIG); + result = SerializeAdapter::serialize(&writeLen, payloadStart, &serializedSize, sizeof(writeLen), + SerializeIF::Endianness::BIG); if (result != HasReturnvaluesIF::RETURN_OK) { return result; } - std::memcpy(this->getPacketData() + sizeof(writeLen), writeData, writeLen); - this->setPacketDataLength(static_cast(writeLen + CRC_SIZE - 1)); - result = addCrc(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; + std::memcpy(payloadStart + sizeof(writeLen), writeData, writeLen); + spParams.setPayloadLen(static_cast(writeLen) + 4); + updateFields(); + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; } - return HasReturnvaluesIF::RETURN_OK; + return calcCrc(); } private: @@ -396,21 +392,23 @@ class TcFlashWrite : public TcBase { /** * @brief Class to help creation of flash delete command. */ -class TcFlashDelete : public TcBase { +class TcFlashDelete : public SpacePacketBase { public: - TcFlashDelete(uint16_t sequenceCount) : TcBase(apid::TC_FLASHDELETE, sequenceCount) {} + TcFlashDelete(SpBaseParams params, uint16_t sequenceCount) + : SpacePacketBase(params, apid::TC_FLASHDELETE, sequenceCount) {} - ReturnValue_t createPacket(std::string filename) { + ReturnValue_t buildPacket(std::string filename) { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; size_t nameSize = filename.size(); - std::memcpy(this->getPacketData(), filename.c_str(), nameSize); - *(this->getPacketData() + nameSize) = NULL_TERMINATOR; - this->setPacketDataLength(nameSize + sizeof(NULL_TERMINATOR) + CRC_SIZE - 1); - result = addCrc(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; + std::memcpy(payloadStart, filename.c_str(), nameSize); + *(payloadStart + nameSize) = NULL_TERMINATOR; + spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR)); + updateFields(); + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; } - return result; + return calcCrc(); } }; @@ -419,17 +417,8 @@ class TcFlashDelete : public TcBase { */ class TcReplayStop : public TcBase { public: - TcReplayStop(uint16_t sequenceCount) : TcBase(apid::TC_REPLAY_STOP, sequenceCount) {} - - ReturnValue_t createPacket() { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - result = addCrc(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - this->setPacketDataLength(static_cast(CRC_SIZE - 1)); - return HasReturnvaluesIF::RETURN_OK; - } + TcReplayStop(SpBaseParams params, uint16_t sequenceCount) + : TcBase(params, apid::TC_REPLAY_STOP, sequenceCount) {} }; /** @@ -440,10 +429,11 @@ class TcReplayStart : public TcBase { /** * @brief Constructor */ - TcReplayStart(uint16_t sequenceCount) : TcBase(apid::TC_REPLAY_START, sequenceCount) {} + TcReplayStart(SpBaseParams params, uint16_t sequenceCount) + : TcBase(params, apid::TC_REPLAY_START, sequenceCount) {} protected: - ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) { + ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; result = lengthCheck(commandDataLen); if (result != HasReturnvaluesIF::RETURN_OK) { @@ -453,8 +443,8 @@ class TcReplayStart : public TcBase { if (result != HasReturnvaluesIF::RETURN_OK) { return result; } - std::memcpy(this->localData.fields.buffer, commandData, commandDataLen); - this->setPacketDataLength(commandDataLen + CRC_SIZE - 1); + std::memcpy(payloadStart, commandData, commandDataLen); + spParams.setPayloadLen(commandDataLen); return result; } @@ -488,10 +478,11 @@ class TcDownlinkPwrOn : public TcBase { /** * @brief Constructor */ - TcDownlinkPwrOn(uint16_t sequenceCount) : TcBase(apid::TC_DOWNLINK_PWR_ON, sequenceCount) {} + TcDownlinkPwrOn(SpBaseParams params, uint16_t sequenceCount) + : TcBase(params, apid::TC_DOWNLINK_PWR_ON, sequenceCount) {} protected: - ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) { + ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; result = lengthCheck(commandDataLen); if (result != HasReturnvaluesIF::RETURN_OK) { @@ -505,10 +496,9 @@ class TcDownlinkPwrOn : public TcBase { if (result != HasReturnvaluesIF::RETURN_OK) { return result; } - std::memcpy(this->localData.fields.buffer, commandData, commandDataLen); - std::memcpy(this->localData.fields.buffer + commandDataLen, &MAX_AMPLITUDE, - sizeof(MAX_AMPLITUDE)); - this->setPacketDataLength(commandDataLen + sizeof(MAX_AMPLITUDE) + CRC_SIZE - 1); + std::memcpy(payloadStart, commandData, commandDataLen); + std::memcpy(payloadStart + commandDataLen, &MAX_AMPLITUDE, sizeof(MAX_AMPLITUDE)); + spParams.setPayloadLen(commandDataLen + sizeof(MAX_AMPLITUDE)); return result; } @@ -555,17 +545,8 @@ class TcDownlinkPwrOn : public TcBase { */ class TcDownlinkPwrOff : public TcBase { public: - TcDownlinkPwrOff(uint16_t sequenceCount) : TcBase(apid::TC_DOWNLINK_PWR_OFF, sequenceCount) {} - - ReturnValue_t createPacket() { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - result = addCrc(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - this->setPacketDataLength(static_cast(CRC_SIZE - 1)); - return HasReturnvaluesIF::RETURN_OK; - } + TcDownlinkPwrOff(SpBaseParams params, uint16_t sequenceCount) + : TcBase(params, apid::TC_DOWNLINK_PWR_OFF, sequenceCount) {} }; /** @@ -576,19 +557,19 @@ class TcReplayWriteSeq : public TcBase { /** * @brief Constructor */ - TcReplayWriteSeq(uint16_t sequenceCount) - : TcBase(apid::TC_REPLAY_WRITE_SEQUENCE, sequenceCount) {} + TcReplayWriteSeq(SpBaseParams params, uint16_t sequenceCount) + : TcBase(params, apid::TC_REPLAY_WRITE_SEQUENCE, sequenceCount) {} protected: - ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) { + ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; result = lengthCheck(commandDataLen); if (result != HasReturnvaluesIF::RETURN_OK) { return result; } - std::memcpy(this->localData.fields.buffer, commandData, commandDataLen); - *(this->localData.fields.buffer + commandDataLen) = NULL_TERMINATOR; - this->setPacketDataLength(commandDataLen + sizeof(NULL_TERMINATOR) + CRC_SIZE - 1); + std::memcpy(payloadStart, commandData, commandDataLen); + *(payloadStart + commandDataLen) = NULL_TERMINATOR; + spParams.setPayloadLen(commandDataLen + sizeof(NULL_TERMINATOR)); return result; } @@ -643,17 +624,8 @@ class FlashWritePusCmd : public MPSoCReturnValuesIF { */ class TcModeReplay : public TcBase { public: - TcModeReplay(uint16_t sequenceCount) : TcBase(apid::TC_MODE_REPLAY, sequenceCount) {} - - ReturnValue_t createPacket() { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - result = addCrc(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - this->setPacketDataLength(static_cast(CRC_SIZE - 1)); - return HasReturnvaluesIF::RETURN_OK; - } + TcModeReplay(SpBaseParams params, uint16_t sequenceCount) + : TcBase(params, apid::TC_MODE_REPLAY, sequenceCount) {} }; /** @@ -661,36 +633,27 @@ class TcModeReplay : public TcBase { */ class TcModeIdle : public TcBase { public: - TcModeIdle(uint16_t sequenceCount) : TcBase(apid::TC_MODE_IDLE, sequenceCount) {} - - ReturnValue_t createPacket() { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; - result = addCrc(); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - this->setPacketDataLength(static_cast(CRC_SIZE - 1)); - return HasReturnvaluesIF::RETURN_OK; - } + TcModeIdle(SpBaseParams params, uint16_t sequenceCount) + : TcBase(params, apid::TC_MODE_IDLE, sequenceCount) {} }; class TcCamcmdSend : public TcBase { public: - TcCamcmdSend(uint16_t sequenceCount) : TcBase(apid::TC_CAM_CMD_SEND, sequenceCount) {} + TcCamcmdSend(SpBaseParams params, uint16_t sequenceCount) + : TcBase(params, apid::TC_CAM_CMD_SEND, sequenceCount) {} protected: - ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) { + ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override { if (commandDataLen > MAX_DATA_LENGTH) { return INVALID_LENGTH; } uint16_t dataLen = static_cast(commandDataLen + sizeof(CARRIAGE_RETURN)); size_t size = sizeof(dataLen); - SerializeAdapter::serialize(&dataLen, this->getPacketData(), &size, sizeof(dataLen), + SerializeAdapter::serialize(&dataLen, payloadStart, &size, sizeof(dataLen), SerializeIF::Endianness::BIG); - std::memcpy(this->getPacketData() + sizeof(dataLen), commandData, commandDataLen); - *(this->getPacketData() + sizeof(dataLen) + commandDataLen) = CARRIAGE_RETURN; - uint16_t trueLength = sizeof(dataLen) + commandDataLen + sizeof(CARRIAGE_RETURN) + CRC_SIZE; - this->setPacketDataLength(trueLength - 1); + std::memcpy(payloadStart + sizeof(dataLen), commandData, commandDataLen); + *(payloadStart + sizeof(dataLen) + commandDataLen) = CARRIAGE_RETURN; + spParams.setPayloadLen(sizeof(dataLen) + commandDataLen + sizeof(CARRIAGE_RETURN)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 56ea8d4a..2b335b66 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -7,8 +7,11 @@ #include #include #include +#include +#include #include "linux/devices/devicedefinitions/SupvReturnValuesIF.h" +#include "mission/devices/devicedefinitions/SpBase.h" namespace supv { @@ -156,12 +159,12 @@ static const size_t MAX_PACKET_SIZE = 1024; static const uint8_t SPACE_PACKET_HEADER_LENGTH = 6; -enum class SequenceFlags : uint8_t { - CONTINUED_PKT = 0b00, - FIRST_PKT = 0b01, - LAST_PKT = 0b10, - STANDALONE_PKT = 0b11 -}; +// enum class SequenceFlags : uint8_t { +// CONTINUED_PKT = 0b00, +// FIRST_PKT = 0b01, +// LAST_PKT = 0b10, +// STANDALONE_PKT = 0b11 +// }; enum PoolIds : lp_id_t { NUM_TMS, @@ -256,7 +259,7 @@ enum PoolIds : lp_id_t { ADC_ENG_15 }; -static constexpr uint16_t DEFAULT_SEQUENCE_COUNT = 1; +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; @@ -275,76 +278,10 @@ static const uint32_t ERASE_MEMORY = 60000; static const uint32_t UPDATE_STATUS_REPORT = 70000; } // namespace recv_timeout -struct SpBaseParams { - SpBaseParams(SpacePacketCreator& creator, uint8_t* buf, size_t maxSize): - creator(creator), buf(buf), maxSize(maxSize) {} - - - void setPayloadLen(size_t payloadLen_) { - payloadLen = payloadLen_; - } - - SpacePacketCreator& creator; - uint8_t* buf; - size_t maxSize; - size_t payloadLen = 0; - -}; - -class SpacePacketBase { -public: - SpacePacketBase(SpBaseParams params) - : spParams(params) { - payloadStart = spParams.buf + ccsds::HEADER_LEN; - updateFields(); - } - - void updateFields() { - spParams.creator.setDataLen(spParams.payloadLen - 1); - spParams.creator.setPacketType(ccsds::PacketType::TC); - } - - ReturnValue_t checkPayloadLen() { - if(ccsds::HEADER_LEN + spParams.payloadLen > spParams.maxSize) { - return SerializeIF::BUFFER_TOO_SHORT; - } - - return result::OK; - } - - ReturnValue_t serializeHeader() { - updateFields(); - size_t serLen = 0; - return spParams.creator.serializeBe(spParams.buf, serLen, spParams.maxSize); - } - - ReturnValue_t checkSizeAndSerializeHeader() { - ReturnValue_t result = checkPayloadLen(); - if(result != result::OK) { - return result; - } - return serializeHeader(); - } - - ReturnValue_t calcCrc() { - /* Calculate crc */ - uint16_t crc = CRC::crc16ccitt(spParams.buf, ccsds::HEADER_LEN + spParams.payloadLen - 2); - - /* Add crc to packet data field of space packet */ - size_t serializedSize = 0; - return SerializeAdapter::serialize(&crc, &payloadStart, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); - } - -protected: - SpBaseParams spParams; - uint8_t* payloadStart; -}; - /** * @brief This class creates a space packet containing only the header data and the CRC. */ -class ApidOnlyPacket: public SpacePacketBase { +class ApidOnlyPacket : public SpacePacketBase { public: /** * @brief Constructor @@ -353,15 +290,14 @@ class ApidOnlyPacket: public SpacePacketBase { * * @note Sequence count of empty packet is always 1. */ - ApidOnlyPacket(SpBaseParams params, uint16_t apid) - : SpacePacketBase(params) { - spParams.setPayloadLen(LENGTH_EMPTY_TC); + ApidOnlyPacket(SpBaseParams params, uint16_t apid) : SpacePacketBase(params) { + spParams.setDataFieldLen(LENGTH_EMPTY_TC); spParams.creator.setApid(apid); } ReturnValue_t buildPacket() { auto res = checkSizeAndSerializeHeader(); - if(res != result::OK) { + if (res != result::OK) { return res; } return calcCrc(); @@ -389,16 +325,15 @@ class MPSoCBootSelect : public SpacePacketBase { * * @note Selection of partitions is currently not supported. */ - MPSoCBootSelect(SpBaseParams params) - : SpacePacketBase(params) { - spParams.setPayloadLen(DATA_FIELD_LENGTH); + MPSoCBootSelect(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SEL_MPSOC_BOOT_IMAGE); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } ReturnValue_t buildPacket(uint8_t mem = 0, uint8_t bp0 = 0, uint8_t bp1 = 0, uint8_t bp2 = 0) { auto res = checkSizeAndSerializeHeader(); - if(res != result::OK) { + if (res != result::OK) { return res; } initPacket(mem, bp0, bp1, bp2); @@ -436,23 +371,21 @@ class EnableNvms : public SpacePacketBase { * @param bp1 Partition pin 1 * @param bp2 Partition pin 2 */ - EnableNvms(SpBaseParams params) - : SpacePacketBase(params) { - spParams.setPayloadLen(DATA_FIELD_LENGTH); + EnableNvms(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_ENABLE_NVMS); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } ReturnValue_t buildPacket(uint8_t nvm01, uint8_t nvm3) { auto res = checkSizeAndSerializeHeader(); - if(res != result::OK) { + if (res != result::OK) { return res; } initPacket(nvm01, nvm3); return calcCrc(); } - private: static const uint8_t DATA_FIELD_LENGTH = 4; static const uint8_t CRC_OFFSET = 2; @@ -468,17 +401,15 @@ class EnableNvms : public SpacePacketBase { */ class SetTimeRef : public SpacePacketBase { public: - SetTimeRef(SpBaseParams params) - : SpacePacketBase(params) { - spParams.setPayloadLen(DATA_FIELD_LENGTH); + SetTimeRef(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_TIME_REF); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } ReturnValue_t buildPacket(Clock::TimeOfDay_t* time) { auto res = checkSizeAndSerializeHeader(); - if(res != result::OK) { + if (res != result::OK) { return res; } initPacket(time); @@ -533,17 +464,15 @@ class SetBootTimeout : public SpacePacketBase { * * @param timeout The boot timeout in milliseconds. */ - SetBootTimeout(SpBaseParams params) - : SpacePacketBase(params) { - spParams.setPayloadLen(DATA_FIELD_LENGTH); + SetBootTimeout(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_BOOT_TIMEOUT); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } ReturnValue_t buildPacket(uint32_t timeout) { auto res = checkSizeAndSerializeHeader(); - if(res != result::OK) { + if (res != result::OK) { return res; } initPacket(timeout); @@ -572,16 +501,15 @@ class SetRestartTries : public SpacePacketBase { * * @param restartTries Maximum restart tries to set. */ - SetRestartTries(SpBaseParams params) - : SpacePacketBase(params) { - spParams.setPayloadLen(DATA_FIELD_LENGTH); + SetRestartTries(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_MAX_RESTART_TRIES); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } ReturnValue_t buildPacket(uint8_t restartTries) { auto res = checkSizeAndSerializeHeader(); - if(res != result::OK) { + if (res != result::OK) { return res; } initPacket(restartTries); @@ -594,9 +522,7 @@ class SetRestartTries : public SpacePacketBase { /** 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; - } + void initPacket(uint8_t restartTries) { payloadStart[0] = restartTries; } }; /** @@ -609,15 +535,15 @@ class DisablePeriodicHkTransmission : public SpacePacketBase { /** * @brief Constructor */ - DisablePeriodicHkTransmission(SpBaseParams params): SpacePacketBase(params) { - spParams.setPayloadLen(DATA_FIELD_LENGTH); + DisablePeriodicHkTransmission(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_DISABLE_HK); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } ReturnValue_t buildPacket() { auto res = checkSizeAndSerializeHeader(); - if(res != result::OK) { + if (res != result::OK) { return res; } initPacket(); @@ -625,13 +551,10 @@ class DisablePeriodicHkTransmission : public SpacePacketBase { } private: - /** Restart tries value (uint8_t) and crc (uint16_t) */ static const uint16_t DATA_FIELD_LENGTH = 3; - void initPacket() { - payloadStart[0] = false; - } + void initPacket() { payloadStart[0] = false; } }; /** @@ -648,11 +571,9 @@ class LatchupAlert : public SpacePacketBase { * @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(SpBaseParams params) - : SpacePacketBase(params) { - spParams.setPayloadLen(DATA_FIELD_LENGTH); + LatchupAlert(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } ReturnValue_t buildPacket(bool state, uint8_t latchupId) { @@ -662,7 +583,7 @@ class LatchupAlert : public SpacePacketBase { spParams.creator.setApid(APID_DISABLE_LATCHUP_ALERT); } auto res = checkSizeAndSerializeHeader(); - if(res != result::OK) { + if (res != result::OK) { return res; } initPacket(latchupId); @@ -676,9 +597,7 @@ class LatchupAlert : public SpacePacketBase { uint8_t latchupId = 0; - void initPacket(uint8_t latchupId) { - payloadStart[0] = latchupId; - } + void initPacket(uint8_t latchupId) { payloadStart[0] = latchupId; } }; class SetAlertlimit : public SpacePacketBase { @@ -690,25 +609,23 @@ class SetAlertlimit : public SpacePacketBase { * 3 - 3.3V, 4 - NVM_4XO, 5 - MISSION, 6 - SAFECOTS) * @param dutycycle */ - SetAlertlimit(SpBaseParams params) - : SpacePacketBase(params) { - spParams.setPayloadLen(DATA_FIELD_LENGTH); + SetAlertlimit(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ALERT_LIMIT); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); - } - ReturnValue_t buildPacket(uint8_t latchupId, uint32_t dutycycle) { - auto res = checkSizeAndSerializeHeader(); - if(res != result::OK) { - return res; - } - res = initPacket(latchupId, dutycycle); - if(res != result::OK) { - return res; - } - return calcCrc(); - } + ReturnValue_t buildPacket(uint8_t latchupId, uint32_t dutycycle) { + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + res = initPacket(latchupId, dutycycle); + if (res != result::OK) { + return res; + } + return calcCrc(); + } private: static const uint16_t DATA_FIELD_LENGTH = 7; @@ -721,7 +638,7 @@ class SetAlertlimit : public SpacePacketBase { payloadStart[0] = latchupId; size_t serLen = 0; return SerializeAdapter::serialize(&dutycycle, payloadStart + 1, &serLen, - sizeof(dutycycle), SerializeIF::Endianness::BIG); + sizeof(dutycycle), SerializeIF::Endianness::BIG); } }; @@ -735,22 +652,18 @@ class SetAdcEnabledChannels : public SpacePacketBase { * * @param ch Defines channels to be enabled or disabled. */ - SetAdcEnabledChannels(SpBaseParams params) - : SpacePacketBase(params) { - spParams.setPayloadLen(DATA_FIELD_LENGTH); + SetAdcEnabledChannels(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ADC_ENABLED_CHANNELS); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } ReturnValue_t buildPacket(uint16_t ch) { auto res = checkSizeAndSerializeHeader(); - if(res != result::OK) { - return res; - } - res = initPacket(ch); - if(res != result::OK) { + if (res != result::OK) { return res; } + initPacket(ch); return calcCrc(); } @@ -762,7 +675,7 @@ class SetAdcEnabledChannels : public SpacePacketBase { void initPacket(uint16_t ch) { size_t serializedSize = 0; SerializeAdapter::serialize(&ch, &payloadStart, &serializedSize, sizeof(ch), - SerializeIF::Endianness::BIG); + SerializeIF::Endianness::BIG); } }; @@ -778,37 +691,33 @@ class SetAdcWindowAndStride : public SpacePacketBase { * @param windowSize * @param stridingStepSize */ - SetAdcWindowAndStride(SpBaseParams params): SpacePacketBase(params) { - spParams.setPayloadLen(DATA_FIELD_LENGTH); + SetAdcWindowAndStride(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ADC_WINDOW_AND_STRIDE); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } - ReturnValue_t buildPacket(uint16_t windowSize, uint16_t stridingStepSize) { - auto res = checkSizeAndSerializeHeader(); - if(res != result::OK) { - return res; - } - res = initPacket(windowSize, stridingStepSize); - if(res != result::OK) { - return res; - } - return calcCrc(); - } + ReturnValue_t buildPacket(uint16_t windowSize, uint16_t stridingStepSize) { + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + initPacket(windowSize, stridingStepSize); + return calcCrc(); + } 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 = 0; uint8_t* data = payloadStart; - SerializeAdapter::serialize(&windowSize, &data, &serializedSize, - sizeof(windowSize), SerializeIF::Endianness::BIG); - SerializeAdapter::serialize(&stridingStepSize, &data, &serializedSize, - sizeof(stridingStepSize), SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&windowSize, &data, &serializedSize, sizeof(windowSize), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&stridingStepSize, &data, &serializedSize, sizeof(stridingStepSize), + SerializeIF::Endianness::BIG); } }; @@ -822,23 +731,21 @@ class SetAdcThreshold : public SpacePacketBase { * * @param threshold */ - SetAdcThreshold(SpBaseParams params): SpacePacketBase(params) { - spParams.setPayloadLen(DATA_FIELD_LENGTH); - spParams.creator.setApid(APID_SET_ADC_THRESHOLD); - spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + SetAdcThreshold(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.creator.setApid(APID_SET_ADC_THRESHOLD); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket(uint32_t threshold) { + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + initPacket(threshold); + return calcCrc(); } - ReturnValue_t buildPacket(uint32_t threshold) { - auto res = checkSizeAndSerializeHeader(); - if(res != result::OK) { - return res; - } - res = initPacket(threshold); - if(res != result::OK) { - return res; - } - return calcCrc(); - } private: static const uint16_t DATA_FIELD_LENGTH = 6; static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; @@ -847,8 +754,8 @@ class SetAdcThreshold : public SpacePacketBase { void initPacket(uint32_t threshold) { size_t serializedSize = 0; - SerializeAdapter::serialize(&threshold, payloadStart, &serializedSize, - sizeof(threshold), SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&threshold, payloadStart, &serializedSize, sizeof(threshold), + SerializeIF::Endianness::BIG); } }; @@ -863,22 +770,20 @@ class RunAutoEmTests : public SpacePacketBase { * @param test 1 - complete EM test, 2 - Short test (only memory readback NVM0,1,3) */ RunAutoEmTests(SpBaseParams params) : SpacePacketBase(params) { - spParams.setPayloadLen(DATA_FIELD_LENGTH); + spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_RUN_AUTO_EM_TESTS); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } - ReturnValue_t buildPacket(uint8_t test) { - auto res = checkSizeAndSerializeHeader(); - if(res != result::OK) { - return res; - } - res = initPacket(test); - if(res != result::OK) { - return res; - } - return calcCrc(); - } + ReturnValue_t buildPacket(uint8_t test) { + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + initPacket(test); + return calcCrc(); + } + private: static const uint16_t DATA_FIELD_LENGTH = 3; static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; @@ -887,15 +792,13 @@ class RunAutoEmTests : public SpacePacketBase { uint8_t test = 0; - void initPacket(uint8_t test) { - payloadStart[0] = test; - } + 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 SpacePacket { +class MramCmd : public SpacePacketBase { public: enum class MramAction { WIPE, DUMP }; @@ -908,30 +811,36 @@ class MramCmd : public SpacePacket { * * @note The content at the stop address is excluded from the dump or wipe operation. */ - MramCmd(uint32_t start, uint32_t stop, MramAction action) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_IDLE_PACKET, DEFAULT_SEQUENCE_COUNT), - start(start), - stop(stop) { + MramCmd(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket(uint32_t start, uint32_t stop, MramAction action) { if (action == MramAction::WIPE) { - this->setAPID(APID_WIPE_MRAM); + spParams.creator.setApid(APID_WIPE_MRAM); } else if (action == MramAction::DUMP) { - this->setAPID(APID_DUMP_MRAM); + spParams.creator.setApid(APID_DUMP_MRAM); } else { sif::debug << "WipeMram: Invalid action specified"; } - initPacket(); + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + initPacket(start, stop); + return calcCrc(); } private: static const uint16_t DATA_FIELD_LENGTH = 8; - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; uint32_t start = 0; uint32_t stop = 0; - void initPacket() { + void initPacket(uint32_t start, uint32_t stop) { uint8_t concatBuffer[6]; concatBuffer[0] = static_cast(start >> 16); concatBuffer[1] = static_cast(start >> 8); @@ -939,14 +848,7 @@ class MramCmd : public SpacePacket { concatBuffer[3] = static_cast(stop >> 16); concatBuffer[4] = static_cast(stop >> 8); concatBuffer[5] = static_cast(stop); - uint8_t* dataFieldPtr = this->localData.fields.buffer; - std::memcpy(dataFieldPtr, concatBuffer, sizeof(concatBuffer)); - size_t serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); + std::memcpy(payloadStart, concatBuffer, sizeof(concatBuffer)); } }; @@ -954,7 +856,7 @@ class MramCmd : public SpacePacket { * @brief This class packages the space packet change the state of a GPIO. This command is only * required for ground testing. */ -class SetGpio : public SpacePacket { +class SetGpio : public SpacePacketBase { public: /** * @brief Constructor @@ -963,12 +865,19 @@ class SetGpio : public SpacePacket { * @param pin * @param val */ - SetGpio(uint8_t port, uint8_t pin, uint8_t val) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_SET_GPIO, DEFAULT_SEQUENCE_COUNT), - port(port), - pin(pin), - val(val) { - initPacket(); + SetGpio(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.creator.setApid(APID_SET_GPIO); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket(uint8_t port, uint8_t pin, uint8_t val) { + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + initPacket(port, pin, val); + return calcCrc(); } private: @@ -981,23 +890,10 @@ class SetGpio : public SpacePacket { uint8_t pin = 0; uint8_t val = 0; - void initPacket() { - size_t serializedSize = 0; - uint8_t* dataFieldPtr = this->localData.fields.buffer; - SerializeAdapter::serialize(&port, &dataFieldPtr, &serializedSize, sizeof(port), - SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&pin, &dataFieldPtr, &serializedSize, sizeof(pin), - SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&val, &dataFieldPtr, &serializedSize, sizeof(val), - SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); + void initPacket(uint8_t port, uint8_t pin, uint8_t val) { + payloadStart[0] = port; + payloadStart[1] = pin; + payloadStart[2] = val; } }; @@ -1005,7 +901,7 @@ class SetGpio : public SpacePacket { * @brief This class packages the space packet causing the supervisor print the state of a GPIO * to the debug output. */ -class ReadGpio : public SpacePacket { +class ReadGpio : public SpacePacketBase { public: /** * @brief Constructor @@ -1013,11 +909,19 @@ class ReadGpio : public SpacePacket { * @param port * @param pin */ - ReadGpio(uint8_t port, uint8_t pin) - : SpacePacket(DATA_FIELD_LENGTH - 1, true, APID_READ_GPIO, DEFAULT_SEQUENCE_COUNT), - port(port), - pin(pin) { - initPacket(); + ReadGpio(SpBaseParams params) : SpacePacketBase(params) { + spParams.setDataFieldLen(DATA_FIELD_LENGTH); + spParams.creator.setApid(APID_READ_GPIO); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket(uint8_t port, uint8_t pin) { + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + initPacket(port, pin); + return calcCrc(); } private: @@ -1029,20 +933,9 @@ class ReadGpio : public SpacePacket { uint8_t port = 0; uint8_t pin = 0; - void initPacket() { - size_t serializedSize = 0; - uint8_t* dataFieldPtr = this->localData.fields.buffer; - SerializeAdapter::serialize(&port, &dataFieldPtr, &serializedSize, sizeof(port), - SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&pin, &dataFieldPtr, &serializedSize, sizeof(pin), - SerializeIF::Endianness::BIG); - serializedSize = 0; - uint16_t crc = CRC::crc16ccitt(this->localData.byteStream, - sizeof(CCSDSPrimaryHeader) + DATA_FIELD_LENGTH - 2); - uint8_t* crcPos = this->localData.fields.buffer + CRC_OFFSET; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); + void initPacket(uint8_t port, uint8_t pin) { + payloadStart[0] = port; + payloadStart[1] = pin; } }; @@ -1054,7 +947,7 @@ class ReadGpio : public SpacePacket { * OP = 0x01: Only the mirror entries will be wiped. * OP = 0x02: Only the circular entries will be wiped. */ -class FactoryReset : public SpacePacket { +class FactoryReset : public SpacePacketBase { public: enum class Op { CLEAR_ALL, MIRROR_ENTRIES, CIRCULAR_ENTRIES }; @@ -1063,98 +956,103 @@ class FactoryReset : public SpacePacket { * * @param op */ - FactoryReset(Op op) : SpacePacket(0, true, APID_FACTORY_RESET, DEFAULT_SEQUENCE_COUNT), op(op) { - initPacket(); + FactoryReset(SpBaseParams params) : SpacePacketBase(params) { + spParams.creator.setApid(APID_FACTORY_RESET); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket(Op op) { + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + initPacket(op); + return calcCrc(); } private: - uint16_t packetLen = 1; // only CRC in data field static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - uint8_t crcOffset = 0; - - Op op = Op::CLEAR_ALL; - - void initPacket() { - uint8_t* dataFieldPtr = this->localData.fields.buffer; - + void initPacket(Op op) { + size_t packetDataLen = 2; switch (op) { case Op::MIRROR_ENTRIES: - *dataFieldPtr = 1; - packetLen = 2; - crcOffset = 1; + payloadStart[0] = 1; + packetDataLen = 3; break; case Op::CIRCULAR_ENTRIES: - *dataFieldPtr = 2; - packetLen = 2; - crcOffset = 1; + payloadStart[0] = 2; + packetDataLen = 3; break; default: break; } - this->setPacketDataLength(packetLen); - size_t serializedSize = 0; - uint16_t crc = - CRC::crc16ccitt(this->localData.byteStream, sizeof(CCSDSPrimaryHeader) + packetLen - 1); - uint8_t* crcPos = this->localData.fields.buffer + crcOffset; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); + spParams.setDataFieldLen(packetDataLen); } }; -class SupvTcSpacePacket : public SpacePacket { - public: - /** - * @brief Constructor - * - * @param payloadDataLen Length of data field without CRC - */ - SupvTcSpacePacket(uint16_t payloadDataLen, uint16_t apid) - : SpacePacket(payloadDataLen + 1, true, apid, DEFAULT_SEQUENCE_COUNT), - payloadDataLen(payloadDataLen) {} +// class SupvTcSpacePacket : public SpacePacketBase { +// public: +// /** +// * @brief Constructor +// * +// * @param payloadDataLen Length of data field without CRC +// */ +// SupvTcSpacePacket(SpBaseParams params): SpacePacketBase(params) { +// spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); +// } +// +// ReturnValue_t buildPacket(uint16_t payloadDataLenWithoutCrc, uint16_t apid) { +// spParams.setPayloadLen(payloadDataLenWithoutCrc + 2); +// spParams.creator.setApid(apid); +// auto res = checkSizeAndSerializeHeader(); +// if(res != result::OK) { +// return res; +// } +// return calcCrc(); +// } +// +// private: +// // The sequence count of most of the TC packets for the supervisor is 1. +// static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; +// +// // The size of the payload data (data field without crc size) +// size_t payloadDataLen = 0; +// }; - void makeCrc() { - size_t serializedSize = 0; - uint16_t crc = - CRC::crc16ccitt(this->localData.byteStream, sizeof(CCSDSPrimaryHeader) + payloadDataLen); - uint8_t* crcPos = this->localData.fields.buffer + payloadDataLen; - SerializeAdapter::serialize(&crc, &crcPos, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); +class SetShutdownTimeout : public SpacePacketBase { + public: + SetShutdownTimeout(SpBaseParams params) : SpacePacketBase(params) { + spParams.setPayloadLen(PAYLOAD_LEN); + spParams.creator.setApid(APID_SET_SHUTDOWN_TIMEOUT); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket(uint32_t timeout) { + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + initPacket(timeout); + return calcCrc(); } private: - // The sequence count of most of the TC packets for the supervisor is 1. - static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; - - // The size of the payload data (data field without crc size) - size_t payloadDataLen = 0; -}; - -class SetShutdownTimeout : public SupvTcSpacePacket { - public: - SetShutdownTimeout(uint32_t timeout) - : SupvTcSpacePacket(PACKET_LEN, APID_SET_SHUTDOWN_TIMEOUT), timeout(timeout) { - initPacket(); - makeCrc(); - } - - private: - static const uint16_t PACKET_LEN = 4; // uint32_t timeout + static const uint16_t PAYLOAD_LEN = 4; // uint32_t timeout uint32_t timeout = 0; - void initPacket() { - uint8_t* dataFieldPtr = this->localData.fields.buffer; - size_t serializedSize = 0; - SerializeAdapter::serialize(&timeout, dataFieldPtr, &serializedSize, sizeof(timeout), - SerializeIF::Endianness::BIG); + void initPacket(uint32_t timeout) { + size_t serLen = 0; + SerializeAdapter::serialize(&timeout, payloadStart, &serLen, sizeof(timeout), + SerializeIF::Endianness::BIG); } }; /** * @brief Command to request CRC over memory region of the supervisor. */ -class CheckMemory : public SupvTcSpacePacket { +class CheckMemory : public SpacePacketBase { public: /** * @brief Constructor @@ -1163,13 +1061,19 @@ class CheckMemory : public SupvTcSpacePacket { * @param startAddress Start address of CRC calculation * @param length Length in bytes of memory region */ - CheckMemory(uint8_t memoryId, uint32_t startAddress, uint32_t length) - : SupvTcSpacePacket(PAYLOAD_LENGTH, APID_CHECK_MEMORY), - memoryId(memoryId), - startAddress(startAddress), - length(length) { - initPacket(); - makeCrc(); + CheckMemory(SpBaseParams params) : SpacePacketBase(params) { + spParams.setPayloadLen(PAYLOAD_LENGTH); + spParams.creator.setApid(APID_CHECK_MEMORY); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + initPacket(memoryId, startAddress, length); + return calcCrc(); } private: @@ -1180,27 +1084,23 @@ class CheckMemory : public SupvTcSpacePacket { uint32_t startAddress = 0; uint32_t length = 0; - void initPacket() { - size_t serializedSize = 0; - uint8_t* dataFieldPtr = this->localData.fields.buffer; - SerializeAdapter::serialize(&memoryId, &dataFieldPtr, &serializedSize, - sizeof(memoryId), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&n, &dataFieldPtr, &serializedSize, sizeof(n), - SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&startAddress, &dataFieldPtr, &serializedSize, - sizeof(startAddress), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&length, &dataFieldPtr, &serializedSize, sizeof(length), - SerializeIF::Endianness::BIG); + void initPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { + uint8_t* data = payloadStart; + size_t serLen = 0; + SerializeAdapter::serialize(&memoryId, &data, &serLen, sizeof(memoryId), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&n, &data, &serLen, sizeof(n), SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&startAddress, &data, &serLen, sizeof(startAddress), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&length, &data, &serLen, sizeof(length), + SerializeIF::Endianness::BIG); } }; /** * @brief This class packages the space packet transporting a part of an MPSoC update. */ -class WriteMemory : public SupvTcSpacePacket { +class WriteMemory : public SpacePacketBase { public: /** * @brief Constructor @@ -1209,53 +1109,54 @@ class WriteMemory : public SupvTcSpacePacket { * @param sequenceCount Sequence count (first update packet expects 1 as sequence count) * @param updateData Pointer to buffer containing update data */ - WriteMemory(SequenceFlags seqFlags, uint16_t sequenceCount, uint8_t memoryId, - uint32_t startAddress, uint16_t length, uint8_t* updateData) - : SupvTcSpacePacket(META_DATA_LENGTH + length, APID_WRITE_MEMORY), - memoryId(memoryId), - startAddress(startAddress), - length(length) { - if (this->length > CHUNK_MAX) { - sif::error << "WriteMemory::WriteMemory: Invalid length" << std::endl; - } - initPacket(updateData); - this->setSequenceFlags(static_cast(seqFlags)); - this->setPacketSequenceCount(sequenceCount); - makeCrc(); + WriteMemory(SpBaseParams params) : SpacePacketBase(params) { + spParams.creator.setApid(APID_WRITE_MEMORY); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } + ReturnValue_t buildPacket(ccsds::SequenceFlags seqFlags, uint16_t sequenceCount, uint8_t memoryId, + uint32_t startAddress, uint16_t length, uint8_t* updateData) { + if (length > CHUNK_MAX + 1) { + sif::error << "WriteMemory::WriteMemory: Invalid length" << std::endl; + return SerializeIF::BUFFER_TOO_SHORT; + } + spParams.creator.setSeqFlags(seqFlags); + spParams.creator.setSeqCount(sequenceCount); + initPacket(memoryId, startAddress, length, updateData); + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + return calcCrc(); + } // 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. static const uint16_t CHUNK_MAX = 512; private: static const uint16_t META_DATA_LENGTH = 8; - - uint8_t memoryId = 0; uint8_t n = 1; - uint32_t startAddress = 0; - uint16_t length = 0; - void initPacket(uint8_t* updateData) { + void initPacket(uint8_t memoryId, uint32_t startAddr, uint16_t updateDataLen, + uint8_t* updateData) { size_t serializedSize = 0; - uint8_t* dataFieldPtr = this->localData.fields.buffer; - SerializeAdapter::serialize(&memoryId, &dataFieldPtr, &serializedSize, - sizeof(memoryId), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&n, &dataFieldPtr, &serializedSize, sizeof(n), - SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&startAddress, &dataFieldPtr, &serializedSize, - sizeof(startAddress), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&length, &dataFieldPtr, &serializedSize, sizeof(length), - SerializeIF::Endianness::BIG); - std::memcpy(dataFieldPtr, updateData, length); - if (length % 2 != 0) { - this->setPacketDataLength(length + sizeof(CCSDSPrimaryHeader) + CRC_SIZE - 1); + uint8_t* data = payloadStart; + SerializeAdapter::serialize(&memoryId, &data, &serializedSize, sizeof(memoryId), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&n, &data, &serializedSize, sizeof(n), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&startAddr, &data, &serializedSize, sizeof(startAddr), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&updateDataLen, &data, &serializedSize, sizeof(updateDataLen), + SerializeIF::Endianness::BIG); + std::memcpy(data, updateData, updateDataLen); + if (updateDataLen % 2 != 0) { + spParams.setPayloadLen(META_DATA_LENGTH + updateDataLen + 1); // 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 - *(dataFieldPtr + length + 1) = 0; + *(data + updateDataLen + 1) = 0; + } else { + spParams.setPayloadLen(META_DATA_LENGTH + updateDataLen); } } }; @@ -1263,15 +1164,21 @@ class WriteMemory : public SupvTcSpacePacket { /** * @brief This class can be used to package the update available or update verify command. */ -class EraseMemory : public SupvTcSpacePacket { +class EraseMemory : public SpacePacketBase { public: - EraseMemory(uint8_t memoryId, uint32_t startAddress, uint32_t length) - : SupvTcSpacePacket(PAYLOAD_LENGTH, APID_ERASE_MEMORY), - memoryId(memoryId), - startAddress(startAddress), - length(length) { - initPacket(); - makeCrc(); + EraseMemory(SpBaseParams params) : SpacePacketBase(params) { + spParams.setPayloadLen(PAYLOAD_LENGTH); + spParams.creator.setApid(APID_ERASE_MEMORY); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + initPacket(memoryId, startAddress, length); + return calcCrc(); } private: @@ -1282,31 +1189,40 @@ class EraseMemory : public SupvTcSpacePacket { uint32_t startAddress = 0; uint32_t length = 0; - void initPacket() { + void initPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { size_t serializedSize = 0; - uint8_t* dataFieldPtr = this->localData.fields.buffer; - SerializeAdapter::serialize(&memoryId, &dataFieldPtr, &serializedSize, - sizeof(memoryId), SerializeIF::Endianness::BIG); + uint8_t* data = payloadStart; + SerializeAdapter::serialize(&memoryId, &data, &serializedSize, sizeof(memoryId), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&n, &data, &serializedSize, sizeof(n), + SerializeIF::Endianness::BIG); serializedSize = 0; - SerializeAdapter::serialize(&n, &dataFieldPtr, &serializedSize, sizeof(n), - SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&startAddress, &data, &serializedSize, sizeof(startAddress), + SerializeIF::Endianness::BIG); serializedSize = 0; - SerializeAdapter::serialize(&startAddress, &dataFieldPtr, &serializedSize, - sizeof(startAddress), SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&length, &dataFieldPtr, &serializedSize, sizeof(length), - SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&length, &data, &serializedSize, sizeof(length), + SerializeIF::Endianness::BIG); } }; /** * @brief This class creates the space packet to enable the auto TM generation */ -class EnableAutoTm : public SupvTcSpacePacket { +class EnableAutoTm : public SpacePacketBase { public: - EnableAutoTm() : SupvTcSpacePacket(PAYLOAD_LENGTH, APID_AUTO_TM) { - *(this->localData.fields.buffer) = ENABLE; - makeCrc(); + EnableAutoTm(SpBaseParams params) : SpacePacketBase(params) { + spParams.setPayloadLen(PAYLOAD_LENGTH); + spParams.creator.setApid(APID_AUTO_TM); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket() { + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + payloadStart[0] = ENABLE; + return calcCrc(); } private: @@ -1317,11 +1233,21 @@ class EnableAutoTm : public SupvTcSpacePacket { /** * @brief This class creates the space packet to disable the auto TM generation */ -class DisableAutoTm : public SupvTcSpacePacket { +class DisableAutoTm : public SpacePacketBase { public: - DisableAutoTm() : SupvTcSpacePacket(PAYLOAD_LENGTH, APID_AUTO_TM) { - *(this->localData.fields.buffer) = DISABLE; - makeCrc(); + DisableAutoTm(SpBaseParams params) : SpacePacketBase(params) { + spParams.setPayloadLen(PAYLOAD_LENGTH); + spParams.creator.setApid(APID_AUTO_TM); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket() { + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + payloadStart[0] = DISABLE; + return calcCrc(); } private: @@ -1332,7 +1258,7 @@ class DisableAutoTm : public SupvTcSpacePacket { /** * @brief This class creates the space packet to request the logging data from the supervisor */ -class RequestLoggingData : public SupvTcSpacePacket { +class RequestLoggingData : public SpacePacketBase { public: enum class Sa : uint8_t { REQUEST_COUNTERS = 1, @@ -1341,11 +1267,20 @@ class RequestLoggingData : public SupvTcSpacePacket { SET_LOGGING_TOPIC = 4 }; - RequestLoggingData(Sa sa, uint8_t tpc = 0) - : SupvTcSpacePacket(PAYLOAD_LENGTH, APID_REQUEST_LOGGING_DATA) { - *(this->localData.fields.buffer) = static_cast(sa); - *(this->localData.fields.buffer + TPC_OFFSET) = tpc; - makeCrc(); + RequestLoggingData(SpBaseParams params) : SpacePacketBase(params) { + spParams.setPayloadLen(PAYLOAD_LENGTH); + spParams.creator.setApid(APID_REQUEST_LOGGING_DATA); + spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); + } + + ReturnValue_t buildPacket(Sa sa, uint8_t tpc = 0) { + auto res = checkSizeAndSerializeHeader(); + if (res != result::OK) { + return res; + } + payloadStart[0] = static_cast(sa); + payloadStart[1] = tpc; + return calcCrc(); } private: @@ -1356,23 +1291,34 @@ class RequestLoggingData : public SupvTcSpacePacket { /** * @brief Class for handling tm replies of the supervisor. */ -class TmPacket : public SpacePacket { +class TmPacket : public SpacePacketReader { public: + TmPacket() = default; /** * @brief Constructor creates idle packet and sets length field to maximum allowed size. */ - TmPacket() : SpacePacket(PACKET_MAX_SIZE) {} + TmPacket(const uint8_t* buf, size_t maxSize) : SpacePacketReader(buf, maxSize) {} + + ReturnValue_t setData(const uint8_t* buf, size_t maxSize) { + return setReadOnlyData(buf, maxSize); + } + + ReturnValue_t check() { + if (isNull()) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return checkSize(); + } /** * @brief Returns the payload data length (data field length without CRC) */ - uint16_t getPayloadDataLength() { return this->getPacketDataLength() - 1; } + uint16_t getPayloadDataLength() { return getPacketDataLen() - 2; } ReturnValue_t checkCrc() { - uint8_t* crcPtr = this->getPacketData() + this->getPayloadDataLength(); + const uint8_t* crcPtr = getFullData() + getFullPacketLen() - CRC_SIZE; uint16_t receivedCrc = *(crcPtr) << 8 | *(crcPtr + 1); - uint16_t recalculatedCrc = - CRC::crc16ccitt(this->localData.byteStream, this->getFullSize() - CRC_SIZE); + uint16_t recalculatedCrc = CRC::crc16ccitt(getFullData(), getFullPacketLen() - CRC_SIZE); if (recalculatedCrc != receivedCrc) { return SupvReturnValuesIF::CRC_FAILURE; } @@ -1382,7 +1328,7 @@ class TmPacket : public SpacePacket { class VerificationReport : public TmPacket { public: - VerificationReport() : TmPacket() {} + VerificationReport(const uint8_t* buf, size_t maxSize) : TmPacket(buf, maxSize) {} /** * @brief Gets the APID of command which caused the transmission of this verification report. @@ -1390,7 +1336,7 @@ class VerificationReport : public TmPacket { uint16_t getRefApid() { uint16_t refApid = 0; size_t size = 0; - uint8_t* refApidPtr = this->getPacketData(); + const uint8_t* refApidPtr = this->getPacketData(); ReturnValue_t result = SerializeAdapter::deSerialize(&refApid, refApidPtr, &size, SerializeIF::Endianness::BIG); if (result != HasReturnvaluesIF::RETURN_OK) { @@ -1403,7 +1349,7 @@ class VerificationReport : public TmPacket { uint16_t getStatusCode() { uint16_t statusCode = 0; size_t size = 0; - uint8_t* statusCodePtr = this->getPacketData() + OFFSET_STATUS_CODE; + const uint8_t* statusCodePtr = this->getPacketData() + OFFSET_STATUS_CODE; ReturnValue_t result = SerializeAdapter::deSerialize(&statusCode, statusCodePtr, &size, SerializeIF::Endianness::BIG); if (result != HasReturnvaluesIF::RETURN_OK) { @@ -1421,10 +1367,10 @@ class VerificationReport : public TmPacket { class AcknowledgmentReport : public VerificationReport { public: - AcknowledgmentReport() : VerificationReport() {} + AcknowledgmentReport(const uint8_t* buf, size_t maxSize) : VerificationReport(buf, maxSize) {} ReturnValue_t checkApid() { - uint16_t apid = this->getAPID(); + uint16_t apid = this->getApid(); if (apid == APID_ACK_SUCCESS) { return HasReturnvaluesIF::RETURN_OK; } else if (apid == APID_ACK_FAILURE) { @@ -1495,10 +1441,10 @@ class AcknowledgmentReport : public VerificationReport { class ExecutionReport : public VerificationReport { public: - ExecutionReport() : VerificationReport() {} + ExecutionReport(const uint8_t* buf, size_t maxSize) : VerificationReport(buf, maxSize) {} ReturnValue_t checkApid() { - uint16_t apid = this->getAPID(); + uint16_t apid = this->getApid(); if (apid == APID_EXE_SUCCESS) { return HasReturnvaluesIF::RETURN_OK; } else if (apid == APID_EXE_FAILURE) { @@ -1926,14 +1872,15 @@ class LoggingReport : public StaticLocalDataSet { class UpdateStatusReport : public TmPacket { public: - UpdateStatusReport() : TmPacket() {} + UpdateStatusReport() = default; + UpdateStatusReport(const uint8_t* buf, size_t maxSize) : TmPacket(buf, maxSize) {} ReturnValue_t parseDataField() { ReturnValue_t result = lengthCheck(); if (result != HasReturnvaluesIF::RETURN_OK) { return result; } - uint8_t* dataFieldPtr = this->localData.fields.buffer; + const uint8_t* dataFieldPtr = getFullData() + ccsds::HEADER_LEN; size_t size = sizeof(memoryId); SerializeAdapter::deSerialize(&memoryId, dataFieldPtr, &size, SerializeIF::Endianness::BIG); dataFieldPtr += size; @@ -1973,7 +1920,7 @@ class UpdateStatusReport : public TmPacket { uint16_t crc = 0; ReturnValue_t lengthCheck() { - if (this->getFullSize() != FULL_SIZE) { + if (getFullPacketLen() != FULL_SIZE) { return SupvReturnValuesIF::UPDATE_STATUS_REPORT_INVALID_LENGTH; } return HasReturnvaluesIF::RETURN_OK; diff --git a/linux/devices/ploc/PlocMPSoCHandler.cpp b/linux/devices/ploc/PlocMPSoCHandler.cpp index 37372b3b..238c8178 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.cpp +++ b/linux/devices/ploc/PlocMPSoCHandler.cpp @@ -206,6 +206,9 @@ ReturnValue_t PlocMPSoCHandler::buildTransitionDeviceCommand(DeviceCommandId_t* ReturnValue_t PlocMPSoCHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand, const uint8_t* commandData, size_t commandDataLen) { + spParams.buf = commandBuffer; + spParams.maxSize = sizeof(commandBuffer); + ReturnValue_t result = RETURN_OK; switch (deviceCommand) { case (mpsoc::TC_MEM_WRITE): { @@ -286,16 +289,23 @@ void PlocMPSoCHandler::fillCommandAndReplyMap() { this->insertInReplyMap(mpsoc::ACK_REPORT, 3, nullptr, mpsoc::SIZE_ACK_REPORT); this->insertInReplyMap(mpsoc::EXE_REPORT, 3, nullptr, mpsoc::SIZE_EXE_REPORT); this->insertInReplyMap(mpsoc::TM_MEMORY_READ_REPORT, 2, nullptr, mpsoc::SIZE_TM_MEM_READ_REPORT); - this->insertInReplyMap(mpsoc::TM_CAM_CMD_RPT, 2, nullptr, SpacePacket::PACKET_MAX_SIZE); + this->insertInReplyMap(mpsoc::TM_CAM_CMD_RPT, 2, nullptr, mpsoc::SP_MAX_SIZE); } ReturnValue_t PlocMPSoCHandler::scanForReply(const uint8_t* start, size_t remainingSize, DeviceCommandId_t* foundId, size_t* foundLen) { ReturnValue_t result = RETURN_OK; - SpacePacket spacePacket; - std::memcpy(spacePacket.getWholeData(), start, remainingSize); - uint16_t apid = spacePacket.getAPID(); + SpacePacketReader spacePacket; + spacePacket.setReadOnlyData(start, remainingSize); + if (spacePacket.isNull()) { + return RETURN_FAILED; + } + auto res = spacePacket.checkSize(); + if (res != RETURN_OK) { + return res; + } + uint16_t apid = spacePacket.getApid(); switch (apid) { case (mpsoc::apid::ACK_SUCCESS): @@ -311,7 +321,7 @@ ReturnValue_t PlocMPSoCHandler::scanForReply(const uint8_t* start, size_t remain *foundId = mpsoc::TM_MEMORY_READ_REPORT; break; case (mpsoc::apid::TM_CAM_CMD_RPT): - *foundLen = spacePacket.getFullSize(); + *foundLen = spacePacket.getFullPacketLen(); tmCamCmdRpt.rememberSpacePacketSize = *foundLen; *foundId = mpsoc::TM_CAM_CMD_RPT; break; @@ -394,13 +404,13 @@ ReturnValue_t PlocMPSoCHandler::prepareTcMemWrite(const uint8_t* commandData, size_t commandDataLen) { ReturnValue_t result = RETURN_OK; sequenceCount++; - mpsoc::TcMemWrite tcMemWrite(sequenceCount); - result = tcMemWrite.createPacket(commandData, commandDataLen); + mpsoc::TcMemWrite tcMemWrite(spParams, sequenceCount); + result = tcMemWrite.buildPacket(commandData, commandDataLen); if (result != RETURN_OK) { sequenceCount--; return result; } - copyToCommandBuffer(&tcMemWrite); + finishTcPrep(); return RETURN_OK; } @@ -408,13 +418,13 @@ ReturnValue_t PlocMPSoCHandler::prepareTcMemRead(const uint8_t* commandData, size_t commandDataLen) { ReturnValue_t result = RETURN_OK; sequenceCount++; - mpsoc::TcMemRead tcMemRead(sequenceCount); - result = tcMemRead.createPacket(commandData, commandDataLen); + mpsoc::TcMemRead tcMemRead(spParams, sequenceCount); + result = tcMemRead.buildPacket(commandData, commandDataLen); if (result != RETURN_OK) { sequenceCount--; return result; } - copyToCommandBuffer(&tcMemRead); + finishTcPrep(); tmMemReadReport.rememberRequestedSize = tcMemRead.getMemLen() * 4 + TmMemReadReport::FIX_SIZE; return RETURN_OK; } @@ -426,14 +436,14 @@ ReturnValue_t PlocMPSoCHandler::prepareTcFlashDelete(const uint8_t* commandData, } ReturnValue_t result = RETURN_OK; sequenceCount++; - mpsoc::TcFlashDelete tcFlashDelete(sequenceCount); - result = tcFlashDelete.createPacket( + mpsoc::TcFlashDelete tcFlashDelete(spParams, sequenceCount); + result = tcFlashDelete.buildPacket( std::string(reinterpret_cast(commandData), commandDataLen)); if (result != RETURN_OK) { sequenceCount--; return result; } - copyToCommandBuffer(&tcFlashDelete); + finishTcPrep(); return RETURN_OK; } @@ -441,26 +451,26 @@ ReturnValue_t PlocMPSoCHandler::prepareTcReplayStart(const uint8_t* commandData, size_t commandDataLen) { ReturnValue_t result = RETURN_OK; sequenceCount++; - mpsoc::TcReplayStart tcReplayStart(sequenceCount); - result = tcReplayStart.createPacket(commandData, commandDataLen); + mpsoc::TcReplayStart tcReplayStart(spParams, sequenceCount); + result = tcReplayStart.buildPacket(commandData, commandDataLen); if (result != RETURN_OK) { sequenceCount--; return result; } - copyToCommandBuffer(&tcReplayStart); + finishTcPrep(); return RETURN_OK; } ReturnValue_t PlocMPSoCHandler::prepareTcReplayStop() { ReturnValue_t result = RETURN_OK; sequenceCount++; - mpsoc::TcReplayStop tcReplayStop(sequenceCount); - result = tcReplayStop.createPacket(); + mpsoc::TcReplayStop tcReplayStop(spParams, sequenceCount); + result = tcReplayStop.buildPacket(); if (result != RETURN_OK) { sequenceCount--; return result; } - copyToCommandBuffer(&tcReplayStop); + finishTcPrep(); return RETURN_OK; } @@ -468,26 +478,26 @@ ReturnValue_t PlocMPSoCHandler::prepareTcDownlinkPwrOn(const uint8_t* commandDat size_t commandDataLen) { ReturnValue_t result = RETURN_OK; sequenceCount++; - mpsoc::TcDownlinkPwrOn tcDownlinkPwrOn(sequenceCount); - result = tcDownlinkPwrOn.createPacket(commandData, commandDataLen); + mpsoc::TcDownlinkPwrOn tcDownlinkPwrOn(spParams, sequenceCount); + result = tcDownlinkPwrOn.buildPacket(commandData, commandDataLen); if (result != RETURN_OK) { sequenceCount--; return result; } - copyToCommandBuffer(&tcDownlinkPwrOn); + finishTcPrep(); return RETURN_OK; } ReturnValue_t PlocMPSoCHandler::prepareTcDownlinkPwrOff() { ReturnValue_t result = RETURN_OK; sequenceCount++; - mpsoc::TcDownlinkPwrOff tcDownlinkPwrOff(sequenceCount); - result = tcDownlinkPwrOff.createPacket(); + mpsoc::TcDownlinkPwrOff tcDownlinkPwrOff(spParams, sequenceCount); + result = tcDownlinkPwrOff.buildPacket(); if (result != RETURN_OK) { sequenceCount--; return result; } - copyToCommandBuffer(&tcDownlinkPwrOff); + finishTcPrep(); return RETURN_OK; } @@ -495,45 +505,39 @@ ReturnValue_t PlocMPSoCHandler::prepareTcReplayWriteSequence(const uint8_t* comm size_t commandDataLen) { ReturnValue_t result = RETURN_OK; sequenceCount++; - mpsoc::TcReplayWriteSeq tcReplayWriteSeq(sequenceCount); - result = tcReplayWriteSeq.createPacket(commandData, commandDataLen); + mpsoc::TcReplayWriteSeq tcReplayWriteSeq(spParams, sequenceCount); + result = tcReplayWriteSeq.buildPacket(commandData, commandDataLen); if (result != RETURN_OK) { sequenceCount--; return result; } - copyToCommandBuffer(&tcReplayWriteSeq); + finishTcPrep(); return RETURN_OK; } ReturnValue_t PlocMPSoCHandler::prepareTcModeReplay() { ReturnValue_t result = RETURN_OK; sequenceCount++; - mpsoc::TcModeReplay tcModeReplay(sequenceCount); - result = tcModeReplay.createPacket(); + mpsoc::TcModeReplay tcModeReplay(spParams, sequenceCount); + result = tcModeReplay.buildPacket(); if (result != RETURN_OK) { sequenceCount--; return result; } - memcpy(commandBuffer, tcModeReplay.getWholeData(), tcModeReplay.getFullSize()); - rawPacket = commandBuffer; - rawPacketLen = tcModeReplay.getFullSize(); - nextReplyId = mpsoc::ACK_REPORT; + finishTcPrep(); return RETURN_OK; } ReturnValue_t PlocMPSoCHandler::prepareTcModeIdle() { ReturnValue_t result = RETURN_OK; sequenceCount++; - mpsoc::TcModeIdle tcModeIdle(sequenceCount); - result = tcModeIdle.createPacket(); + mpsoc::TcModeIdle tcModeIdle(spParams, sequenceCount); + result = tcModeIdle.buildPacket(); if (result != RETURN_OK) { sequenceCount--; return result; } - memcpy(commandBuffer, tcModeIdle.getWholeData(), tcModeIdle.getFullSize()); - rawPacket = commandBuffer; - rawPacketLen = tcModeIdle.getFullSize(); - nextReplyId = mpsoc::ACK_REPORT; + finishTcPrep(); return RETURN_OK; } @@ -541,26 +545,18 @@ ReturnValue_t PlocMPSoCHandler::prepareTcCamCmdSend(const uint8_t* commandData, size_t commandDataLen) { ReturnValue_t result = RETURN_OK; sequenceCount++; - mpsoc::TcCamcmdSend tcCamCmdSend(sequenceCount); - result = tcCamCmdSend.createPacket(commandData, commandDataLen); + mpsoc::TcCamcmdSend tcCamCmdSend(spParams, sequenceCount); + result = tcCamCmdSend.buildPacket(commandData, commandDataLen); if (result != RETURN_OK) { sequenceCount--; return result; } - copyToCommandBuffer(&tcCamCmdSend); + finishTcPrep(); nextReplyId = mpsoc::TM_CAM_CMD_RPT; return RETURN_OK; } -void PlocMPSoCHandler::copyToCommandBuffer(mpsoc::TcBase* tc) { - if (tc == nullptr) { - sif::debug << "PlocMPSoCHandler::copyToCommandBuffer: Invalid TC" << std::endl; - } - memcpy(commandBuffer, tc->getWholeData(), tc->getFullSize()); - rawPacket = commandBuffer; - rawPacketLen = tc->getFullSize(); - nextReplyId = mpsoc::ACK_REPORT; -} +void PlocMPSoCHandler::finishTcPrep() { nextReplyId = mpsoc::ACK_REPORT; } ReturnValue_t PlocMPSoCHandler::verifyPacket(const uint8_t* start, size_t foundLen) { uint16_t receivedCrc = *(start + foundLen - 2) << 8 | *(start + foundLen - 1); @@ -818,7 +814,7 @@ size_t PlocMPSoCHandler::getNextReplyLength(DeviceCommandId_t commandId) { case mpsoc::TM_CAM_CMD_RPT: // Read acknowledgment, camera and execution report in one go because length of camera // report is not fixed - replyLen = SpacePacket::PACKET_MAX_SIZE; + replyLen = mpsoc::SP_MAX_SIZE; break; default: { replyLen = iter->second.replyLen; diff --git a/linux/devices/ploc/PlocMPSoCHandler.h b/linux/devices/ploc/PlocMPSoCHandler.h index 0d3445d1..da3e1744 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.h +++ b/linux/devices/ploc/PlocMPSoCHandler.h @@ -8,7 +8,6 @@ #include "fsfw/action/CommandsActionsIF.h" #include "fsfw/devicehandlers/DeviceHandlerBase.h" #include "fsfw/ipc/QueueFactory.h" -#include "fsfw/tmtcpacket/SpacePacket.h" #include "fsfw/tmtcservices/SourceSequenceCounter.h" #include "fsfw_hal/linux/gpio/Gpio.h" #include "fsfw_hal/linux/uart/UartComIF.h" @@ -111,8 +110,7 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF { // Initiate the sequence count with the maximum value. It is incremented before // a packet is sent, so the first value will be 0 accordingly using // the wrap around of the counter. - SourceSequenceCounter sequenceCount = - SourceSequenceCounter(SpacePacketBase::LIMIT_SEQUENCE_COUNT - 1); + SourceSequenceCounter sequenceCount = SourceSequenceCounter(ccsds::LIMIT_SEQUENCE_COUNT - 1); uint8_t commandBuffer[mpsoc::MAX_COMMAND_SIZE]; @@ -148,11 +146,14 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF { struct TelemetryBuffer { uint16_t length = 0; - uint8_t buffer[SpacePacket::PACKET_MAX_SIZE]; + uint8_t buffer[mpsoc::SP_MAX_SIZE]; }; TelemetryBuffer tmBuffer; + SpacePacketCreator creator; + SpBaseParams spParams = SpBaseParams(creator); + enum class PowerState { OFF, BOOTING, SHUTDOWN, ON }; PowerState powerState = PowerState::OFF; @@ -172,10 +173,7 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF { ReturnValue_t prepareTcReplayWriteSequence(const uint8_t* commandData, size_t commandDataLen); ReturnValue_t prepareTcCamCmdSend(const uint8_t* commandData, size_t commandDataLen); ReturnValue_t prepareTcModeIdle(); - /** - * @brief Copies space packet into command buffer - */ - void copyToCommandBuffer(mpsoc::TcBase* tc); + void finishTcPrep(); /** * @brief This function checks the crc of the received PLOC reply. diff --git a/linux/devices/ploc/PlocMemoryDumper.h b/linux/devices/ploc/PlocMemoryDumper.h index 559e7ec8..a1b4f8de 100644 --- a/linux/devices/ploc/PlocMemoryDumper.h +++ b/linux/devices/ploc/PlocMemoryDumper.h @@ -13,7 +13,6 @@ #include "fsfw/objectmanager/SystemObject.h" #include "fsfw/returnvalues/HasReturnvaluesIF.h" #include "fsfw/tasks/ExecutableObjectIF.h" -#include "fsfw/tmtcpacket/SpacePacket.h" #include "linux/fsfwconfig/objects/systemObjectList.h" /** diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 7d38d0c2..26579caa 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -28,6 +28,11 @@ PlocSupervisorHandler::PlocSupervisorHandler(object_id_t objectId, object_id_t u if (comCookie == NULL) { 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); } @@ -154,6 +159,7 @@ void PlocSupervisorHandler::doStartUp() { uartIsolatorSwitch.pullHigh(); startupState = StartupState::SET_TIME; } + break; } case StartupState::SET_TIME_EXECUTING: break; @@ -194,6 +200,8 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d size_t commandDataLen) { using namespace supv; ReturnValue_t result = RETURN_FAILED; + spParams.buf = commandBuffer; + spParams.maxSize = sizeof(commandBuffer); switch (deviceCommand) { case GET_HK_REPORT: { prepareEmptyCmd(APID_GET_HK_REPORT); @@ -314,21 +322,30 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case FACTORY_RESET_CLEAR_ALL: { - FactoryReset packet(FactoryReset::Op::CLEAR_ALL); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - result = RETURN_OK; + FactoryReset packet(spParams); + result = packet.buildPacket(FactoryReset::Op::CLEAR_ALL); + if (result != RETURN_OK) { + break; + } + finishTcPrep(); break; } case FACTORY_RESET_CLEAR_MIRROR: { - FactoryReset packet(FactoryReset::Op::MIRROR_ENTRIES); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - result = RETURN_OK; + FactoryReset packet(spParams); + result = packet.buildPacket(FactoryReset::Op::MIRROR_ENTRIES); + if (result != RETURN_OK) { + break; + } + finishTcPrep(); break; } case FACTORY_RESET_CLEAR_CIRCULAR: { - FactoryReset packet(FactoryReset::Op::CIRCULAR_ENTRIES); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - result = RETURN_OK; + FactoryReset packet(spParams); + result = packet.buildPacket(FactoryReset::Op::CIRCULAR_ENTRIES); + if (result != RETURN_OK) { + break; + } + finishTcPrep(); break; } case START_MPSOC_QUIET: { @@ -347,34 +364,49 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d break; } case ENABLE_AUTO_TM: { - EnableAutoTm packet; - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - result = RETURN_OK; + EnableAutoTm packet(spParams); + result = packet.buildPacket(); + if (result != RETURN_OK) { + break; + } + finishTcPrep(); break; } case DISABLE_AUTO_TM: { - DisableAutoTm packet; - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - result = RETURN_OK; + DisableAutoTm packet(spParams); + result = packet.buildPacket(); + if (result != RETURN_OK) { + break; + } + finishTcPrep(); break; } case LOGGING_REQUEST_COUNTERS: { - RequestLoggingData packet(RequestLoggingData::Sa::REQUEST_COUNTERS); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - result = RETURN_OK; + RequestLoggingData packet(spParams); + result = packet.buildPacket(RequestLoggingData::Sa::REQUEST_COUNTERS); + if (result != RETURN_OK) { + break; + } + finishTcPrep(); break; } case LOGGING_CLEAR_COUNTERS: { - RequestLoggingData packet(RequestLoggingData::Sa::CLEAR_COUNTERS); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - result = RETURN_OK; + RequestLoggingData packet(spParams); + result = packet.buildPacket(RequestLoggingData::Sa::CLEAR_COUNTERS); + if (result != RETURN_OK) { + break; + } + finishTcPrep(); break; } case LOGGING_SET_TOPIC: { uint8_t tpc = *(commandData); - RequestLoggingData packet(RequestLoggingData::Sa::SET_LOGGING_TOPIC, tpc); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); - result = RETURN_OK; + RequestLoggingData packet(spParams); + result = packet.buildPacket(RequestLoggingData::Sa::SET_LOGGING_TOPIC, tpc); + if (result != RETURN_OK) { + break; + } + finishTcPrep(); break; } case RESET_PL: { @@ -1354,15 +1386,25 @@ void PlocSupervisorHandler::handleDeviceTM(const uint8_t* data, size_t dataSize, } } -void PlocSupervisorHandler::prepareEmptyCmd(uint16_t apid) { - supv::ApidOnlyPacket packet(apid); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); +ReturnValue_t PlocSupervisorHandler::prepareEmptyCmd(uint16_t apid) { + supv::ApidOnlyPacket packet(spParams, apid); + ReturnValue_t result = packet.buildPacket(); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); + return RETURN_OK; } -void PlocSupervisorHandler::prepareSelBootImageCmd(const uint8_t* commandData) { - supv::MPSoCBootSelect packet(*commandData, *(commandData + 1), *(commandData + 2), - *(commandData + 3)); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); +ReturnValue_t PlocSupervisorHandler::prepareSelBootImageCmd(const uint8_t* commandData) { + supv::MPSoCBootSelect packet(spParams); + ReturnValue_t result = + packet.buildPacket(*commandData, *(commandData + 1), *(commandData + 2), *(commandData + 3)); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); + return RETURN_OK; } ReturnValue_t PlocSupervisorHandler::prepareSetTimeRefCmd() { @@ -1373,27 +1415,46 @@ ReturnValue_t PlocSupervisorHandler::prepareSetTimeRefCmd() { << std::endl; return SupvReturnValuesIF::GET_TIME_FAILURE; } - supv::SetTimeRef packet(&time); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + supv::SetTimeRef packet(spParams); + result = packet.buildPacket(&time); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); return RETURN_OK; } -void PlocSupervisorHandler::prepareDisableHk() { - supv::DisablePeriodicHkTransmission packet; - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); +ReturnValue_t PlocSupervisorHandler::prepareDisableHk() { + supv::DisablePeriodicHkTransmission packet(spParams); + ReturnValue_t result = packet.buildPacket(); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); + return RETURN_OK; } -void PlocSupervisorHandler::prepareSetBootTimeoutCmd(const uint8_t* commandData) { +ReturnValue_t PlocSupervisorHandler::prepareSetBootTimeoutCmd(const uint8_t* commandData) { + supv::SetBootTimeout packet(spParams); uint32_t timeout = *(commandData) << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8 | *(commandData + 3); - supv::SetBootTimeout packet(timeout); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + ReturnValue_t result = packet.buildPacket(timeout); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); + return RETURN_OK; } -void PlocSupervisorHandler::prepareRestartTriesCmd(const uint8_t* commandData) { +ReturnValue_t PlocSupervisorHandler::prepareRestartTriesCmd(const uint8_t* commandData) { uint8_t restartTries = *(commandData); - supv::SetRestartTries packet(restartTries); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + supv::SetRestartTries packet(spParams); + ReturnValue_t result = packet.buildPacket(restartTries); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); + return RETURN_OK; } ReturnValue_t PlocSupervisorHandler::prepareLatchupConfigCmd(const uint8_t* commandData, @@ -1405,13 +1466,21 @@ ReturnValue_t PlocSupervisorHandler::prepareLatchupConfigCmd(const uint8_t* comm } switch (deviceCommand) { case (supv::ENABLE_LATCHUP_ALERT): { - supv::LatchupAlert packet(true, latchupId); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + supv::LatchupAlert packet(spParams); + result = packet.buildPacket(true, latchupId); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); break; } case (supv::DISABLE_LATCHUP_ALERT): { - supv::LatchupAlert packet(false, latchupId); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + supv::LatchupAlert packet(spParams); + result = packet.buildPacket(false, latchupId); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); break; } default: { @@ -1433,31 +1502,50 @@ ReturnValue_t PlocSupervisorHandler::prepareSetAlertLimitCmd(const uint8_t* comm if (latchupId > 6) { return SupvReturnValuesIF::INVALID_LATCHUP_ID; } - supv::SetAlertlimit packet(latchupId, dutycycle); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + supv::SetAlertlimit packet(spParams); + ReturnValue_t result = packet.buildPacket(latchupId, dutycycle); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); return RETURN_OK; } -void PlocSupervisorHandler::prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData) { +ReturnValue_t PlocSupervisorHandler::prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData) { uint16_t ch = *(commandData) << 8 | *(commandData + 1); - supv::SetAdcEnabledChannels packet(ch); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + supv::SetAdcEnabledChannels packet(spParams); + ReturnValue_t result = packet.buildPacket(ch); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); + return RETURN_OK; } -void PlocSupervisorHandler::prepareSetAdcWindowAndStrideCmd(const uint8_t* commandData) { +ReturnValue_t PlocSupervisorHandler::prepareSetAdcWindowAndStrideCmd(const uint8_t* commandData) { uint8_t offset = 0; uint16_t windowSize = *(commandData + offset) << 8 | *(commandData + offset + 1); offset += 2; uint16_t stridingStepSize = *(commandData + offset) << 8 | *(commandData + offset + 1); - supv::SetAdcWindowAndStride packet(windowSize, stridingStepSize); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + supv::SetAdcWindowAndStride packet(spParams); + ReturnValue_t result = packet.buildPacket(windowSize, stridingStepSize); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); + return RETURN_OK; } -void PlocSupervisorHandler::prepareSetAdcThresholdCmd(const uint8_t* commandData) { +ReturnValue_t PlocSupervisorHandler::prepareSetAdcThresholdCmd(const uint8_t* commandData) { uint32_t threshold = *(commandData) << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8 | *(commandData + 3); - supv::SetAdcThreshold packet(threshold); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + supv::SetAdcThreshold packet(spParams); + ReturnValue_t result = packet.buildPacket(threshold); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); + return RETURN_OK; } ReturnValue_t PlocSupervisorHandler::prepareRunAutoEmTest(const uint8_t* commandData) { @@ -1465,8 +1553,12 @@ ReturnValue_t PlocSupervisorHandler::prepareRunAutoEmTest(const uint8_t* command if (test != 1 && test != 2) { return SupvReturnValuesIF::INVALID_TEST_PARAM; } - supv::RunAutoEmTests packet(test); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + supv::RunAutoEmTests packet(spParams); + ReturnValue_t result = packet.buildPacket(test); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); return RETURN_OK; } @@ -1479,8 +1571,12 @@ ReturnValue_t PlocSupervisorHandler::prepareWipeMramCmd(const uint8_t* commandDa if ((stop - start) <= 0) { return SupvReturnValuesIF::INVALID_MRAM_ADDRESSES; } - supv::MramCmd packet(start, stop, supv::MramCmd::MramAction::WIPE); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + supv::MramCmd packet(spParams); + ReturnValue_t result = packet.buildPacket(start, stop, supv::MramCmd::MramAction::WIPE); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); return RETURN_OK; } @@ -1490,42 +1586,52 @@ ReturnValue_t PlocSupervisorHandler::prepareDumpMramCmd(const uint8_t* commandDa size_t size = sizeof(start) + sizeof(stop); SerializeAdapter::deSerialize(&start, &commandData, &size, SerializeIF::Endianness::BIG); SerializeAdapter::deSerialize(&stop, &commandData, &size, SerializeIF::Endianness::BIG); - supv::MramCmd packet(start, stop, supv::MramCmd::MramAction::DUMP); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); 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 != RETURN_OK) { + return result; + } expectedMramDumpPackets = (stop - start) / supv::MAX_DATA_CAPACITY; if ((stop - start) % supv::MAX_DATA_CAPACITY) { expectedMramDumpPackets++; } receivedMramDumpPackets = 0; + + finishTcPrep(); return RETURN_OK; } -void PlocSupervisorHandler::prepareSetGpioCmd(const uint8_t* commandData) { +ReturnValue_t PlocSupervisorHandler::prepareSetGpioCmd(const uint8_t* commandData) { uint8_t port = *commandData; uint8_t pin = *(commandData + 1); uint8_t val = *(commandData + 2); - supv::SetGpio packet(port, pin, val); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + supv::SetGpio packet(spParams); + ReturnValue_t result = packet.buildPacket(port, pin, val); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); + return RETURN_OK; } -void PlocSupervisorHandler::prepareReadGpioCmd(const uint8_t* commandData) { +ReturnValue_t PlocSupervisorHandler::prepareReadGpioCmd(const uint8_t* commandData) { uint8_t port = *commandData; uint8_t pin = *(commandData + 1); - supv::ReadGpio packet(port, pin); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + supv::ReadGpio packet(spParams); + ReturnValue_t result = packet.buildPacket(port, pin); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); + return RETURN_OK; } -void PlocSupervisorHandler::packetToOutBuffer(uint8_t* packetData, size_t fullSize) { - memcpy(commandBuffer, packetData, fullSize); - rawPacket = commandBuffer; - rawPacketLen = fullSize; - nextReplyId = supv::ACK_REPORT; -} +void PlocSupervisorHandler::finishTcPrep() { nextReplyId = supv::ACK_REPORT; } -void PlocSupervisorHandler::prepareSetShutdownTimeoutCmd(const uint8_t* commandData) { +ReturnValue_t PlocSupervisorHandler::prepareSetShutdownTimeoutCmd(const uint8_t* commandData) { uint32_t timeout = 0; ReturnValue_t result = RETURN_OK; size_t size = sizeof(timeout); @@ -1536,8 +1642,13 @@ void PlocSupervisorHandler::prepareSetShutdownTimeoutCmd(const uint8_t* commandD << "PlocSupervisorHandler::prepareSetShutdownTimeoutCmd: Failed to deserialize timeout" << std::endl; } - supv::SetShutdownTimeout packet(timeout); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + supv::SetShutdownTimeout packet(spParams); + result = packet.buildPacket(timeout); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); + return RETURN_OK; } ReturnValue_t PlocSupervisorHandler::prepareLoggingRequest(const uint8_t* commandData, @@ -1545,8 +1656,12 @@ ReturnValue_t PlocSupervisorHandler::prepareLoggingRequest(const uint8_t* comman using namespace supv; RequestLoggingData::Sa sa = static_cast(*commandData); uint8_t tpc = *(commandData + 1); - RequestLoggingData packet(sa, tpc); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + RequestLoggingData packet(spParams); + ReturnValue_t result = packet.buildPacket(sa, tpc); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); return RETURN_OK; } @@ -1554,8 +1669,12 @@ ReturnValue_t PlocSupervisorHandler::prepareEnableNvmsCommand(const uint8_t* com using namespace supv; uint8_t nvm01 = *(commandData); uint8_t nvm3 = *(commandData + 1); - EnableNvms packet(nvm01, nvm3); - packetToOutBuffer(packet.getWholeData(), packet.getFullSize()); + EnableNvms packet(spParams); + ReturnValue_t result = packet.buildPacket(nvm01, nvm3); + if (result != RETURN_OK) { + return result; + } + finishTcPrep(); return RETURN_OK; } @@ -1743,8 +1862,8 @@ void PlocSupervisorHandler::increaseExpectedMramReplies(DeviceCommandId_t id) { return; } uint8_t sequenceFlags = spacePacketBuffer[2] >> 6; - if (sequenceFlags != static_cast(supv::SequenceFlags::LAST_PKT) && - (sequenceFlags != static_cast(supv::SequenceFlags::STANDALONE_PKT))) { + if (sequenceFlags != static_cast(ccsds::SequenceFlags::LAST_SEGMENT) && + (sequenceFlags != static_cast(ccsds::SequenceFlags::UNSEGMENTED))) { // Command expects at least one MRAM packet more and the execution report info->expectedReplies = 2; mramReplyInfo->countdown->resetTimer(); @@ -1770,8 +1889,8 @@ ReturnValue_t PlocSupervisorHandler::handleMramDumpFile(DeviceCommandId_t id) { uint16_t packetLen = readSpacePacketLength(spacePacketBuffer); uint8_t sequenceFlags = readSequenceFlags(spacePacketBuffer); if (id == supv::FIRST_MRAM_DUMP) { - if (sequenceFlags == static_cast(supv::SequenceFlags::FIRST_PKT) || - (sequenceFlags == static_cast(supv::SequenceFlags::STANDALONE_PKT))) { + if (sequenceFlags == static_cast(ccsds::SequenceFlags::FIRST_SEGMENT) || + (sequenceFlags == static_cast(ccsds::SequenceFlags::UNSEGMENTED))) { result = createMramDumpFile(); if (result != RETURN_OK) { return result; diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 9946a1d5..ec40cfad 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -100,6 +100,8 @@ class PlocSupervisorHandler : public DeviceHandlerBase { StartupState startupState = StartupState::OFF; uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]; + SpacePacketCreator creator; + SpBaseParams spParams = SpBaseParams(creator); /** * This variable is used to store the id of the next reply to receive. This is necessary @@ -233,14 +235,14 @@ 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. */ - void prepareEmptyCmd(uint16_t apid); + ReturnValue_t prepareEmptyCmd(uint16_t apid); /** * @brief This function initializes the space packet to select the boot image of the MPSoC. */ - void prepareSelBootImageCmd(const uint8_t* commandData); + ReturnValue_t prepareSelBootImageCmd(const uint8_t* commandData); - void prepareDisableHk(); + ReturnValue_t prepareDisableHk(); /** * @brief This function fills the commandBuffer with the data to update the time of the @@ -252,9 +254,9 @@ class PlocSupervisorHandler : public DeviceHandlerBase { * @brief This function fills the commandBuffer with the data to change the boot timeout * value in the PLOC supervisor. */ - void prepareSetBootTimeoutCmd(const uint8_t* commandData); + ReturnValue_t prepareSetBootTimeoutCmd(const uint8_t* commandData); - void prepareRestartTriesCmd(const uint8_t* commandData); + ReturnValue_t prepareRestartTriesCmd(const uint8_t* commandData); /** * @brief This function fills the command buffer with the packet to enable or disable the @@ -271,21 +273,21 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t prepareLatchupConfigCmd(const uint8_t* commandData, DeviceCommandId_t deviceCommand); ReturnValue_t prepareSetAlertLimitCmd(const uint8_t* commandData); - void prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData); - void prepareSetAdcWindowAndStrideCmd(const uint8_t* commandData); - void prepareSetAdcThresholdCmd(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); ReturnValue_t prepareWipeMramCmd(const uint8_t* commandData); ReturnValue_t prepareDumpMramCmd(const uint8_t* commandData); - void prepareSetGpioCmd(const uint8_t* commandData); - void prepareReadGpioCmd(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); /** * @brief Copies the content of a space packet to the command buffer. */ - void packetToOutBuffer(uint8_t* packetData, size_t fullSize); + void finishTcPrep(); /** * @brief In case an acknowledgment failure reply has been received this function disables @@ -363,7 +365,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t createMramDumpFile(); ReturnValue_t getTimeStampString(std::string& timeStamp); - void prepareSetShutdownTimeoutCmd(const uint8_t* commandData); + ReturnValue_t prepareSetShutdownTimeoutCmd(const uint8_t* commandData); ReturnValue_t extractUpdateCommand(const uint8_t* commandData, size_t size, std::string* file, uint8_t* memoryId, uint32_t* startAddress); diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 544a98eb..1c93e7ad 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -16,7 +16,10 @@ #include "mission/utility/ProgressPrinter.h" #include "mission/utility/Timestamp.h" -PlocSupvHelper::PlocSupvHelper(object_id_t objectId) : SystemObject(objectId) {} +PlocSupvHelper::PlocSupvHelper(object_id_t objectId) : SystemObject(objectId) { + spParams.buf = commandBuffer; + spParams.maxSize = sizeof(commandBuffer); +} PlocSupvHelper::~PlocSupvHelper() {} @@ -210,7 +213,7 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { uint8_t tempData[supv::WriteMemory::CHUNK_MAX]; std::ifstream file(update.file, std::ifstream::binary); uint16_t dataLength = 0; - supv::SequenceFlags seqFlags; + ccsds::SequenceFlags seqFlags; while (update.remainingSize > 0) { if (terminate) { terminate = false; @@ -235,14 +238,20 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { return FILE_CLOSED_ACCIDENTALLY; } if (update.bytesWritten == 0) { - seqFlags = supv::SequenceFlags::FIRST_PKT; + seqFlags = ccsds::SequenceFlags::FIRST_SEGMENT; } else if (update.remainingSize == 0) { - seqFlags = supv::SequenceFlags::LAST_PKT; + seqFlags = ccsds::SequenceFlags::LAST_SEGMENT; } else { - seqFlags = supv::SequenceFlags::CONTINUED_PKT; + seqFlags = ccsds::SequenceFlags::CONTINUATION; + } + supv::WriteMemory packet(spParams); + result = packet.buildPacket(seqFlags, update.sequenceCount++, update.memoryId, + update.startAddress + update.bytesWritten, dataLength, tempData); + if (result != RETURN_OK) { + update.sequenceCount--; + triggerEvent(WRITE_MEMORY_FAILED, update.packetNum); + return result; } - supv::WriteMemory packet(seqFlags, update.sequenceCount++, update.memoryId, - update.startAddress + update.bytesWritten, dataLength, tempData); result = handlePacketTransmission(packet); if (result != RETURN_OK) { update.sequenceCount--; @@ -262,7 +271,11 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { ReturnValue_t PlocSupvHelper::performEventBufferRequest() { using namespace supv; ReturnValue_t result = RETURN_OK; - RequestLoggingData packet(RequestLoggingData::Sa::REQUEST_EVENT_BUFFERS); + RequestLoggingData packet(spParams); + result = packet.buildPacket(RequestLoggingData::Sa::REQUEST_EVENT_BUFFERS); + if (result != RETURN_OK) { + return result; + } result = sendCommand(packet); if (result != RETURN_OK) { return result; @@ -284,7 +297,11 @@ ReturnValue_t PlocSupvHelper::performEventBufferRequest() { ReturnValue_t PlocSupvHelper::selectMemory() { ReturnValue_t result = RETURN_OK; - supv::MPSoCBootSelect packet(update.memoryId); + supv::MPSoCBootSelect packet(spParams); + result = packet.buildPacket(update.memoryId); + if (result != RETURN_OK) { + return result; + } result = handlePacketTransmission(packet); if (result != RETURN_OK) { return result; @@ -294,7 +311,8 @@ ReturnValue_t PlocSupvHelper::selectMemory() { ReturnValue_t PlocSupvHelper::prepareUpdate() { ReturnValue_t result = RETURN_OK; - supv::ApidOnlyPacket packet(supv::APID_PREPARE_UPDATE); + supv::ApidOnlyPacket packet(spParams, supv::APID_PREPARE_UPDATE); + result = packet.buildPacket(); result = handlePacketTransmission(packet, PREPARE_UPDATE_EXECUTION_REPORT); if (result != RETURN_OK) { return result; @@ -304,7 +322,11 @@ ReturnValue_t PlocSupvHelper::prepareUpdate() { ReturnValue_t PlocSupvHelper::eraseMemory() { ReturnValue_t result = RETURN_OK; - supv::EraseMemory eraseMemory(update.memoryId, update.startAddress, update.length); + supv::EraseMemory eraseMemory(spParams); + result = eraseMemory.buildPacket(update.memoryId, update.startAddress, update.length); + if (result != RETURN_OK) { + return result; + } result = handlePacketTransmission(eraseMemory, supv::recv_timeout::ERASE_MEMORY); if (result != RETURN_OK) { return result; @@ -312,7 +334,7 @@ ReturnValue_t PlocSupvHelper::eraseMemory() { return RETURN_OK; } -ReturnValue_t PlocSupvHelper::handlePacketTransmission(SpacePacket& packet, +ReturnValue_t PlocSupvHelper::handlePacketTransmission(SpacePacketBase& packet, uint32_t timeoutExecutionReport) { ReturnValue_t result = RETURN_OK; result = sendCommand(packet); @@ -330,10 +352,10 @@ ReturnValue_t PlocSupvHelper::handlePacketTransmission(SpacePacket& packet, return RETURN_OK; } -ReturnValue_t PlocSupvHelper::sendCommand(SpacePacket& packet) { +ReturnValue_t PlocSupvHelper::sendCommand(SpacePacketBase& packet) { ReturnValue_t result = RETURN_OK; - rememberApid = packet.getAPID(); - result = uartComIF->sendMessage(comCookie, packet.getWholeData(), packet.getFullSize()); + rememberApid = packet.getApid(); + result = uartComIF->sendMessage(comCookie, packet.getFullPacket(), packet.getFullPacketLen()); if (result != RETURN_OK) { sif::warning << "PlocSupvHelper::sendCommand: Failed to send command" << std::endl; triggerEvent(SUPV_SENDING_COMMAND_FAILED, result, static_cast(internalState)); @@ -477,7 +499,11 @@ ReturnValue_t PlocSupvHelper::calcImageCrc() { ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { ReturnValue_t result = RETURN_OK; // Verification of update write procedure - supv::CheckMemory packet(update.memoryId, update.startAddress, update.length); + supv::CheckMemory packet(spParams); + result = packet.buildPacket(update.memoryId, update.startAddress, update.length); + if (result != RETURN_OK) { + return result; + } result = sendCommand(packet); if (result != RETURN_OK) { return result; @@ -548,7 +574,7 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception() { file.close(); return result; } - uint16_t apid = tmPacket.getAPID(); + uint16_t apid = tmPacket.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; diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 69d26264..128b4774 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -11,6 +11,7 @@ #include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw_hal/linux/uart/UartComIF.h" #include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h" + #ifdef XIPHOS_Q7S #include "bsp_q7s/memory/SdCardManager.h" #endif @@ -176,6 +177,8 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha SdCardManager* sdcMan = nullptr; #endif uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]; + SpacePacketCreator creator; + SpBaseParams spParams = SpBaseParams(creator); bool terminate = false; @@ -195,9 +198,9 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha ReturnValue_t continueUpdate(); ReturnValue_t writeUpdatePackets(); ReturnValue_t performEventBufferRequest(); - ReturnValue_t handlePacketTransmission(SpacePacket& packet, + ReturnValue_t handlePacketTransmission(SpacePacketBase& packet, uint32_t timeoutExecutionReport = 60000); - ReturnValue_t sendCommand(SpacePacket& packet); + ReturnValue_t sendCommand(SpacePacketBase& packet); /** * @brief Function which reads form the communication interface * diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index c7309097..1df383b6 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -1,9 +1,9 @@ -#include #include "AcsController.h" +#include + AcsController::AcsController(object_id_t objectId) - : ExtendedControllerBase(objectId, objects::NO_OBJECT), - mgmData(this) {} + : ExtendedControllerBase(objectId, objects::NO_OBJECT), mgmData(this) {} ReturnValue_t AcsController::handleCommandMessage(CommandMessage *message) { return HasReturnvaluesIF::RETURN_OK; @@ -30,8 +30,8 @@ void AcsController::performControlOperation() { } if (mgmData.read() == RETURN_OK) { - copyMgmData(); - mgmData.commit(); + copyMgmData(); + mgmData.commit(); } } @@ -56,31 +56,31 @@ ReturnValue_t AcsController::checkModeCommand(Mode_t mode, Submode_t submode, void AcsController::copyMgmData() { { PoolReadGuard pg(&mgm0Lis3Set); - if(pg.getReadResult() == RETURN_OK) { + if (pg.getReadResult() == RETURN_OK) { std::memcpy(mgmData.mgm0Lis3.value, mgm0Lis3Set.fieldStrengths.value, 3 * sizeof(float)); } } { PoolReadGuard pg(&mgm1Rm3100Set); - if(pg.getReadResult() == RETURN_OK) { + if (pg.getReadResult() == RETURN_OK) { std::memcpy(mgmData.mgm1Rm3100.value, mgm1Rm3100Set.fieldStrengths.value, 3 * sizeof(float)); } } { PoolReadGuard pg(&mgm2Lis3Set); - if(pg.getReadResult() == RETURN_OK) { + if (pg.getReadResult() == RETURN_OK) { std::memcpy(mgmData.mgm2Lis3.value, mgm2Lis3Set.fieldStrengths.value, 3 * sizeof(float)); } } { PoolReadGuard pg(&mgm3Rm3100Set); - if(pg.getReadResult() == RETURN_OK) { + if (pg.getReadResult() == RETURN_OK) { std::memcpy(mgmData.mgm3Rm3100.value, mgm3Rm3100Set.fieldStrengths.value, 3 * sizeof(float)); } } { PoolReadGuard pg(&imtqMgmSet); - if(pg.getReadResult() == RETURN_OK) { + if (pg.getReadResult() == RETURN_OK) { std::memcpy(mgmData.imtqCal.value, imtqMgmSet.mgmXyz.value, 3 * sizeof(int32_t)); mgmData.actuationCalStatus.value = imtqMgmSet.coilActuationStatus.value; } diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index c5b43288..06ab289c 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -2,8 +2,9 @@ #define MISSION_CONTROLLER_ACSCONTROLLER_H_ #include -#include "controllerdefinitions/AcsCtrlDefinitions.h" #include + +#include "controllerdefinitions/AcsCtrlDefinitions.h" #include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" #include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" #include "mission/devices/devicedefinitions/IMTQHandlerDefinitions.h" @@ -33,11 +34,16 @@ class AcsController : public ExtendedControllerBase { // MGMs acsctrl::MgmData mgmData; - MGMLIS3MDL::MgmPrimaryDataset mgm0Lis3Set = MGMLIS3MDL::MgmPrimaryDataset(objects::MGM_0_LIS3_HANDLER); - RM3100::Rm3100PrimaryDataset mgm1Rm3100Set = RM3100::Rm3100PrimaryDataset(objects::MGM_1_RM3100_HANDLER); - MGMLIS3MDL::MgmPrimaryDataset mgm2Lis3Set = MGMLIS3MDL::MgmPrimaryDataset(objects::MGM_2_LIS3_HANDLER); - RM3100::Rm3100PrimaryDataset mgm3Rm3100Set = RM3100::Rm3100PrimaryDataset(objects::MGM_3_RM3100_HANDLER); - IMTQ::CalibratedMtmMeasurementSet imtqMgmSet = IMTQ::CalibratedMtmMeasurementSet(objects::IMTQ_HANDLER); + MGMLIS3MDL::MgmPrimaryDataset mgm0Lis3Set = + MGMLIS3MDL::MgmPrimaryDataset(objects::MGM_0_LIS3_HANDLER); + RM3100::Rm3100PrimaryDataset mgm1Rm3100Set = + RM3100::Rm3100PrimaryDataset(objects::MGM_1_RM3100_HANDLER); + MGMLIS3MDL::MgmPrimaryDataset mgm2Lis3Set = + MGMLIS3MDL::MgmPrimaryDataset(objects::MGM_2_LIS3_HANDLER); + RM3100::Rm3100PrimaryDataset mgm3Rm3100Set = + RM3100::Rm3100PrimaryDataset(objects::MGM_3_RM3100_HANDLER); + IMTQ::CalibratedMtmMeasurementSet imtqMgmSet = + IMTQ::CalibratedMtmMeasurementSet(objects::IMTQ_HANDLER); PoolEntry mgm0PoolVec = PoolEntry(3); PoolEntry mgm1PoolVec = PoolEntry(3); diff --git a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h index 9062ef6b..b1ddb9df 100644 --- a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h +++ b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h @@ -1,15 +1,14 @@ #ifndef MISSION_CONTROLLER_CONTROLLERDEFINITIONS_ACSCTRLDEFINITIONS_H_ #define MISSION_CONTROLLER_CONTROLLERDEFINITIONS_ACSCTRLDEFINITIONS_H_ -#include #include +#include + #include namespace acsctrl { -enum SetIds : uint32_t { - MGM_SENSOR_DATA -}; +enum SetIds : uint32_t { MGM_SENSOR_DATA }; enum PoolIds : lp_id_t { MGM_0_LIS3_UT, @@ -20,14 +19,13 @@ enum PoolIds : lp_id_t { MGM_IMTQ_CAL_ACT_STATUS }; - static constexpr uint8_t MGM_SET_ENTRIES = 5; /** * @brief This dataset can be used to store the collected temperatures of all temperature sensors */ class MgmData : public StaticLocalDataSet { -public: + public: MgmData(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, MGM_SENSOR_DATA) {} // The ACS board measurement are in floating point uT @@ -37,12 +35,12 @@ public: lp_vec_t mgm3Rm3100 = lp_vec_t(sid.objectId, MGM_3_RM3100_UT, this); // The IMTQ measurements are in integer nT lp_vec_t imtqCal = lp_vec_t(sid.objectId, MGM_IMTQ_CAL_NT, this); - lp_var_t actuationCalStatus = lp_var_t(sid.objectId, - MGM_IMTQ_CAL_ACT_STATUS, this); -private: + lp_var_t actuationCalStatus = + lp_var_t(sid.objectId, MGM_IMTQ_CAL_ACT_STATUS, this); + private: }; -} +} // namespace acsctrl #endif /* MISSION_CONTROLLER_CONTROLLERDEFINITIONS_ACSCTRLDEFINITIONS_H_ */ diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index fbfb16f2..01fe4e9b 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -91,14 +91,17 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_) { pus::PUS_SERVICE_2, 3, 10); new Service3Housekeeping(objects::PUS_SERVICE_3_HOUSEKEEPING, apid::EIVE_OBSW, pus::PUS_SERVICE_3); - new Service5EventReporting(PsbParams(objects::PUS_SERVICE_5_EVENT_REPORTING, apid::EIVE_OBSW, - pus::PUS_SERVICE_5), 15, 45); + new Service5EventReporting( + PsbParams(objects::PUS_SERVICE_5_EVENT_REPORTING, apid::EIVE_OBSW, pus::PUS_SERVICE_5), 15, + 45); new Service8FunctionManagement(objects::PUS_SERVICE_8_FUNCTION_MGMT, apid::EIVE_OBSW, pus::PUS_SERVICE_8, 3, 60); - new Service9TimeManagement(PsbParams(objects::PUS_SERVICE_9_TIME_MGMT, apid::EIVE_OBSW, pus::PUS_SERVICE_9)); + new Service9TimeManagement( + PsbParams(objects::PUS_SERVICE_9_TIME_MGMT, apid::EIVE_OBSW, pus::PUS_SERVICE_9)); new Service11TelecommandScheduling( - PsbParams(objects::PUS_SERVICE_11_TC_SCHEDULER, apid::EIVE_OBSW, pus::PUS_SERVICE_11), ccsdsDistrib); + PsbParams(objects::PUS_SERVICE_11_TC_SCHEDULER, apid::EIVE_OBSW, pus::PUS_SERVICE_11), + ccsdsDistrib); new Service17Test(PsbParams(objects::PUS_SERVICE_17_TEST, apid::EIVE_OBSW, pus::PUS_SERVICE_17)); new Service20ParameterManagement(objects::PUS_SERVICE_20_PARAMETERS, apid::EIVE_OBSW, pus::PUS_SERVICE_20); diff --git a/mission/devices/IMTQHandler.cpp b/mission/devices/IMTQHandler.cpp index 98b67e96..91e378ca 100644 --- a/mission/devices/IMTQHandler.cpp +++ b/mission/devices/IMTQHandler.cpp @@ -753,13 +753,13 @@ void IMTQHandler::fillCalibratedMtmDataset(const uint8_t* packet) { calMtmMeasurementSet.setValidity(true, true); int8_t offset = 2; calMtmMeasurementSet.mgmXyz[0] = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 | - *(packet + offset + 1) << 8 | *(packet + offset); + *(packet + offset + 1) << 8 | *(packet + offset); offset += 4; calMtmMeasurementSet.mgmXyz[1] = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 | - *(packet + offset + 1) << 8 | *(packet + offset); + *(packet + offset + 1) << 8 | *(packet + offset); offset += 4; calMtmMeasurementSet.mgmXyz[2] = *(packet + offset + 3) << 24 | *(packet + offset + 2) << 16 | - *(packet + offset + 1) << 8 | *(packet + offset); + *(packet + offset + 1) << 8 | *(packet + offset); offset += 4; calMtmMeasurementSet.coilActuationStatus = (*(packet + offset + 3) << 24) | (*(packet + offset + 2) << 16) | diff --git a/mission/devices/PCDUHandler.h b/mission/devices/PCDUHandler.h index 98be1f38..21bb869d 100644 --- a/mission/devices/PCDUHandler.h +++ b/mission/devices/PCDUHandler.h @@ -30,8 +30,7 @@ class PCDUHandler : public PowerSwitchIF, virtual ReturnValue_t initialize() override; virtual ReturnValue_t performOperation(uint8_t counter) override; - virtual void handleChangedDataset(sid_t sid, - store_address_t storeId = store_address_t::invalid(), + virtual void handleChangedDataset(sid_t sid, store_address_t storeId = store_address_t::invalid(), bool* clearMessage = nullptr) override; virtual ReturnValue_t sendSwitchCommand(uint8_t switchNr, ReturnValue_t onOff) override; diff --git a/mission/devices/devicedefinitions/SpBase.h b/mission/devices/devicedefinitions/SpBase.h new file mode 100644 index 00000000..ba73904e --- /dev/null +++ b/mission/devices/devicedefinitions/SpBase.h @@ -0,0 +1,83 @@ +#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_SPBASE_H_ +#define MISSION_DEVICES_DEVICEDEFINITIONS_SPBASE_H_ + +#include + +#include + +struct SpBaseParams { + SpBaseParams(SpacePacketCreator& creator) : creator(creator) {} + + SpBaseParams(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_; } + + SpacePacketCreator& creator; + uint8_t* buf = nullptr; + size_t maxSize = 0; + size_t dataFieldLen = 0; +}; + +class SpacePacketBase { + public: + SpacePacketBase(SpBaseParams params) : spParams(params) { updateFields(); } + + SpacePacketBase(SpBaseParams params, uint16_t apid, uint16_t seqCount) : spParams(params) { + spParams.creator.setApid(apid); + spParams.creator.setSeqCount(seqCount); + updateFields(); + } + + void updateFields() { + payloadStart = spParams.buf + ccsds::HEADER_LEN; + spParams.creator.setDataLen(spParams.dataFieldLen - 1); + spParams.creator.setPacketType(ccsds::PacketType::TC); + } + + const uint8_t* getFullPacket() const { return spParams.buf; } + + size_t getFullPacketLen() const { return spParams.creator.getFullPacketLen(); } + + uint16_t getApid() const { return spParams.creator.getApid(); } + + ReturnValue_t checkPayloadLen() { + if (ccsds::HEADER_LEN + spParams.dataFieldLen > spParams.maxSize) { + return SerializeIF::BUFFER_TOO_SHORT; + } + + return result::OK; + } + + ReturnValue_t serializeHeader() { + updateFields(); + size_t serLen = 0; + return spParams.creator.serializeBe(spParams.buf, serLen, spParams.maxSize); + } + + ReturnValue_t checkSizeAndSerializeHeader() { + ReturnValue_t result = checkPayloadLen(); + if (result != result::OK) { + return result; + } + return serializeHeader(); + } + + ReturnValue_t calcCrc() { + /* Calculate crc */ + uint16_t crc = CRC::crc16ccitt(spParams.buf, ccsds::HEADER_LEN + spParams.dataFieldLen - 2); + + /* Add crc to packet data field of space packet */ + size_t serializedSize = 0; + return SerializeAdapter::serialize(&crc, &payloadStart, &serializedSize, sizeof(crc), + SerializeIF::Endianness::BIG); + } + + protected: + SpBaseParams spParams; + uint8_t* payloadStart; +}; + +#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_SPBASE_H_ */ diff --git a/mission/tmtc/TmFunnel.cpp b/mission/tmtc/TmFunnel.cpp index 30caa1c5..c23da16d 100644 --- a/mission/tmtc/TmFunnel.cpp +++ b/mission/tmtc/TmFunnel.cpp @@ -11,8 +11,11 @@ object_id_t TmFunnel::downlinkDestination = objects::NO_OBJECT; object_id_t TmFunnel::storageDestination = objects::NO_OBJECT; TmFunnel::TmFunnel(object_id_t objectId, CdsShortTimeStamper& timeReader, uint32_t messageDepth, - uint8_t reportReceptionVc) - : SystemObject(objectId), timeReader(timeReader), messageDepth(messageDepth), reportReceptionVc(reportReceptionVc) { + uint8_t reportReceptionVc) + : SystemObject(objectId), + timeReader(timeReader), + messageDepth(messageDepth), + reportReceptionVc(reportReceptionVc) { auto mqArgs = MqArgs(objectId, static_cast(this)); tmQueue = QueueFactory::instance()->createMessageQueue( messageDepth, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs); @@ -54,14 +57,13 @@ ReturnValue_t TmFunnel::handlePacket(TmTcMessage* message) { PusTmZeroCopyWriter packet(timeReader, packetData, size); result = packet.parseDataWithoutCrcCheck(); - if(result != HasReturnvaluesIF::RETURN_OK) { + if (result != HasReturnvaluesIF::RETURN_OK) { return result; } packet.setSequenceCount(sourceSequenceCount++); sourceSequenceCount = sourceSequenceCount % ccsds::LIMIT_SEQUENCE_COUNT; packet.updateErrorControl(); - result = tmQueue->sendToDefault(message); if (result != HasReturnvaluesIF::RETURN_OK) { tmStore->deleteData(message->getStorageId()); diff --git a/mission/tmtc/TmFunnel.h b/mission/tmtc/TmFunnel.h index 98e581e9..f4c9d14e 100644 --- a/mission/tmtc/TmFunnel.h +++ b/mission/tmtc/TmFunnel.h @@ -24,7 +24,8 @@ class TmFunnel : public AcceptsTelemetryIF, public ExecutableObjectIF, public Sy friend void(Factory::setStaticFrameworkObjectIds)(); public: - TmFunnel(object_id_t objectId, CdsShortTimeStamper& timeReader, uint32_t messageDepth = 20, uint8_t reportReceptionVc = 0); + TmFunnel(object_id_t objectId, CdsShortTimeStamper& timeReader, uint32_t messageDepth = 20, + uint8_t reportReceptionVc = 0); virtual ~TmFunnel(); virtual MessageQueueId_t getReportReceptionQueue(uint8_t virtualChannel = 0) override; From 7e3517d309cf0e3f2ee90dffc4ae70a101afccda Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 15 Aug 2022 18:34:26 +0200 Subject: [PATCH 05/58] it compiles again --- bsp_q7s/core/CoreController.cpp | 3 +- bsp_q7s/core/ObjectFactory.cpp | 7 +- linux/devices/GPSHyperionLinuxController.cpp | 3 +- .../devicedefinitions/PlocMPSoCDefinitions.h | 72 +++----- .../PlocSupervisorDefinitions.h | 171 ++++++------------ linux/devices/ploc/PlocMPSoCHandler.cpp | 7 +- linux/devices/ploc/PlocMPSoCHandler.h | 5 +- linux/devices/ploc/PlocMPSoCHelper.cpp | 67 +++++-- linux/devices/ploc/PlocMPSoCHelper.h | 15 +- linux/devices/ploc/PlocSupervisorHandler.cpp | 33 +++- linux/devices/ploc/PlocSupervisorHandler.h | 4 +- linux/devices/ploc/PlocSupvHelper.cpp | 59 +++--- linux/devices/ploc/PlocSupvHelper.h | 12 +- mission/devices/devicedefinitions/SpBase.h | 50 ++++- 14 files changed, 259 insertions(+), 249 deletions(-) diff --git a/bsp_q7s/core/CoreController.cpp b/bsp_q7s/core/CoreController.cpp index e387aa71..1f07fbb3 100644 --- a/bsp_q7s/core/CoreController.cpp +++ b/bsp_q7s/core/CoreController.cpp @@ -92,7 +92,8 @@ ReturnValue_t CoreController::initializeLocalDataPool(localpool::DataPool &local localDataPoolMap.emplace(core::TEMPERATURE, new PoolEntry({0})); localDataPoolMap.emplace(core::PS_VOLTAGE, new PoolEntry({0})); localDataPoolMap.emplace(core::PL_VOLTAGE, new PoolEntry({0})); - poolManager.subscribeForPeriodicPacket(hkSet.getSid(), false, 10.0, false); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(hkSet.getSid(), false, 10.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/bsp_q7s/core/ObjectFactory.cpp b/bsp_q7s/core/ObjectFactory.cpp index 43b1da31..3ac765ff 100644 --- a/bsp_q7s/core/ObjectFactory.cpp +++ b/bsp_q7s/core/ObjectFactory.cpp @@ -95,8 +95,8 @@ ResetArgs RESET_ARGS_GNSS; void Factory::setStaticFrameworkObjectIds() { - PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; - PusServiceBase::packetDestination = objects::TM_FUNNEL; + PusServiceBase::PUS_DISTRIBUTOR = objects::PUS_PACKET_DISTRIBUTOR; + PusServiceBase::PACKET_DESTINATION = objects::TM_FUNNEL; CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; @@ -117,8 +117,7 @@ void Factory::setStaticFrameworkObjectIds() { LocalDataPoolManager::defaultHkDestination = objects::PUS_SERVICE_3_HOUSEKEEPING; - VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; - TmPacketBase::timeStamperId = objects::TIME_STAMPER; + VerificationReporter::DEFAULT_RECEIVER = objects::PUS_SERVICE_1_VERIFICATION; } void ObjectFactory::setStatics() { Factory::setStaticFrameworkObjectIds(); } diff --git a/linux/devices/GPSHyperionLinuxController.cpp b/linux/devices/GPSHyperionLinuxController.cpp index 5d97554a..81e0b951 100644 --- a/linux/devices/GPSHyperionLinuxController.cpp +++ b/linux/devices/GPSHyperionLinuxController.cpp @@ -87,7 +87,8 @@ ReturnValue_t GPSHyperionLinuxController::initializeLocalDataPool( localDataPoolMap.emplace(GpsHyperion::SATS_IN_USE, new PoolEntry()); localDataPoolMap.emplace(GpsHyperion::SATS_IN_VIEW, new PoolEntry()); localDataPoolMap.emplace(GpsHyperion::FIX_MODE, new PoolEntry()); - poolManager.subscribeForPeriodicPacket(gpsSet.getSid(), false, 30.0, false); + poolManager.subscribeForRegularPeriodicPacket( + subdp::RegularHkPeriodicParams(gpsSet.getSid(), false, 30.0)); return HasReturnvaluesIF::RETURN_OK; } diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index 5ec211b2..adcd4271 100644 --- a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h +++ b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h @@ -136,7 +136,7 @@ static const uint16_t RESERVED_4 = 0x5F4; /** * @brief Abstract base class for TC space packet of MPSoC. */ -class TcBase : public SpacePacketBase, public MPSoCReturnValuesIF { +class TcBase : public ploc::SpTcBase, public MPSoCReturnValuesIF { public: virtual ~TcBase() = default; @@ -149,8 +149,8 @@ class TcBase : public SpacePacketBase, public MPSoCReturnValuesIF { * @param sequenceCount Sequence count of space packet which will be incremented with each * sent and received packets. */ - TcBase(SpBaseParams params, uint16_t apid, uint16_t sequenceCount) - : SpacePacketBase(params, apid, sequenceCount) { + TcBase(ploc::SpTcParams params, uint16_t apid, uint16_t sequenceCount) + : ploc::SpTcBase(params, apid, sequenceCount) { spParams.setDataFieldLen(INIT_LENGTH); } @@ -194,28 +194,6 @@ class TcBase : public SpacePacketBase, public MPSoCReturnValuesIF { } }; -/** - * @brief Class for handling tm replies of the PLOC MPSoC. - */ -class TmPacket : public SpacePacket, public MPSoCReturnValuesIF { - public: - /** - * @brief Constructor creates idle packet and sets length field to maximum allowed size. - */ - TmPacket() : SpacePacket(PACKET_MAX_SIZE) {} - - ReturnValue_t checkCrc() { - uint8_t* crcPtr = this->getPacketData() + this->getPacketDataLength() - 1; - uint16_t receivedCrc = *(crcPtr) << 8 | *(crcPtr + 1); - uint16_t recalculatedCrc = - CRC::crc16ccitt(this->localData.byteStream, this->getFullSize() - CRC_SIZE); - if (recalculatedCrc != receivedCrc) { - return CRC_FAILURE; - } - return HasReturnvaluesIF::RETURN_OK; - } -}; - /** * @brief This class helps to build the memory read command for the PLOC. */ @@ -224,7 +202,7 @@ class TcMemRead : public TcBase { /** * @brief Constructor */ - TcMemRead(SpBaseParams params, uint16_t sequenceCount) + TcMemRead(ploc::SpTcParams params, uint16_t sequenceCount) : TcBase(params, apid::TC_MEM_READ, sequenceCount) { spParams.setPayloadLen(COMMAND_LENGTH); } @@ -276,7 +254,7 @@ class TcMemWrite : public TcBase { /** * @brief Constructor */ - TcMemWrite(SpBaseParams params, uint16_t sequenceCount) + TcMemWrite(ploc::SpTcParams params, uint16_t sequenceCount) : TcBase(params, apid::TC_MEM_WRITE, sequenceCount) {} protected: @@ -312,10 +290,10 @@ class TcMemWrite : public TcBase { /** * @brief Class to help creation of flash fopen command. */ -class FlashFopen : public SpacePacketBase { +class FlashFopen : public ploc::SpTcBase { public: - FlashFopen(SpBaseParams params, uint16_t sequenceCount) - : SpacePacketBase(params, apid::TC_FLASHFOPEN, sequenceCount) {} + FlashFopen(ploc::SpTcParams params, uint16_t sequenceCount) + : ploc::SpTcBase(params, apid::TC_FLASHFOPEN, sequenceCount) {} static const char APPEND = 'a'; static const char WRITE = 'w'; @@ -323,7 +301,6 @@ class FlashFopen : public SpacePacketBase { ReturnValue_t createPacket(std::string filename, char accessMode_) { accessMode = accessMode_; - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; size_t nameSize = filename.size(); std::memcpy(payloadStart, filename.c_str(), nameSize); *(spParams.buf + nameSize) = NULL_TERMINATOR; @@ -342,7 +319,7 @@ class FlashFopen : public SpacePacketBase { */ class FlashFclose : public TcBase { public: - FlashFclose(SpBaseParams params, uint16_t sequenceCount) + FlashFclose(ploc::SpTcParams params, uint16_t sequenceCount) : TcBase(params, apid::TC_FLASHFCLOSE, sequenceCount) {} ReturnValue_t createPacket(std::string filename) { @@ -357,12 +334,12 @@ class FlashFclose : public TcBase { /** * @brief Class to build flash write space packet. */ -class TcFlashWrite : public SpacePacketBase { +class TcFlashWrite : public ploc::SpTcBase { public: - TcFlashWrite(SpBaseParams params, uint16_t sequenceCount) - : SpacePacketBase(params, apid::TC_FLASHWRITE, sequenceCount) {} + TcFlashWrite(ploc::SpTcParams params, uint16_t sequenceCount) + : ploc::SpTcBase(params, apid::TC_FLASHWRITE, sequenceCount) {} - ReturnValue_t createPacket(const uint8_t* writeData, uint32_t writeLen_) { + ReturnValue_t buildPacket(const uint8_t* writeData, uint32_t writeLen_) { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; writeLen = writeLen_; if (writeLen > MAX_DATA_SIZE) { @@ -392,13 +369,12 @@ class TcFlashWrite : public SpacePacketBase { /** * @brief Class to help creation of flash delete command. */ -class TcFlashDelete : public SpacePacketBase { +class TcFlashDelete : public ploc::SpTcBase { public: - TcFlashDelete(SpBaseParams params, uint16_t sequenceCount) - : SpacePacketBase(params, apid::TC_FLASHDELETE, sequenceCount) {} + TcFlashDelete(ploc::SpTcParams params, uint16_t sequenceCount) + : ploc::SpTcBase(params, apid::TC_FLASHDELETE, sequenceCount) {} ReturnValue_t buildPacket(std::string filename) { - ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; size_t nameSize = filename.size(); std::memcpy(payloadStart, filename.c_str(), nameSize); *(payloadStart + nameSize) = NULL_TERMINATOR; @@ -417,7 +393,7 @@ class TcFlashDelete : public SpacePacketBase { */ class TcReplayStop : public TcBase { public: - TcReplayStop(SpBaseParams params, uint16_t sequenceCount) + TcReplayStop(ploc::SpTcParams params, uint16_t sequenceCount) : TcBase(params, apid::TC_REPLAY_STOP, sequenceCount) {} }; @@ -429,7 +405,7 @@ class TcReplayStart : public TcBase { /** * @brief Constructor */ - TcReplayStart(SpBaseParams params, uint16_t sequenceCount) + TcReplayStart(ploc::SpTcParams params, uint16_t sequenceCount) : TcBase(params, apid::TC_REPLAY_START, sequenceCount) {} protected: @@ -478,7 +454,7 @@ class TcDownlinkPwrOn : public TcBase { /** * @brief Constructor */ - TcDownlinkPwrOn(SpBaseParams params, uint16_t sequenceCount) + TcDownlinkPwrOn(ploc::SpTcParams params, uint16_t sequenceCount) : TcBase(params, apid::TC_DOWNLINK_PWR_ON, sequenceCount) {} protected: @@ -545,7 +521,7 @@ class TcDownlinkPwrOn : public TcBase { */ class TcDownlinkPwrOff : public TcBase { public: - TcDownlinkPwrOff(SpBaseParams params, uint16_t sequenceCount) + TcDownlinkPwrOff(ploc::SpTcParams params, uint16_t sequenceCount) : TcBase(params, apid::TC_DOWNLINK_PWR_OFF, sequenceCount) {} }; @@ -557,7 +533,7 @@ class TcReplayWriteSeq : public TcBase { /** * @brief Constructor */ - TcReplayWriteSeq(SpBaseParams params, uint16_t sequenceCount) + TcReplayWriteSeq(ploc::SpTcParams params, uint16_t sequenceCount) : TcBase(params, apid::TC_REPLAY_WRITE_SEQUENCE, sequenceCount) {} protected: @@ -624,7 +600,7 @@ class FlashWritePusCmd : public MPSoCReturnValuesIF { */ class TcModeReplay : public TcBase { public: - TcModeReplay(SpBaseParams params, uint16_t sequenceCount) + TcModeReplay(ploc::SpTcParams params, uint16_t sequenceCount) : TcBase(params, apid::TC_MODE_REPLAY, sequenceCount) {} }; @@ -633,13 +609,13 @@ class TcModeReplay : public TcBase { */ class TcModeIdle : public TcBase { public: - TcModeIdle(SpBaseParams params, uint16_t sequenceCount) + TcModeIdle(ploc::SpTcParams params, uint16_t sequenceCount) : TcBase(params, apid::TC_MODE_IDLE, sequenceCount) {} }; class TcCamcmdSend : public TcBase { public: - TcCamcmdSend(SpBaseParams params, uint16_t sequenceCount) + TcCamcmdSend(ploc::SpTcParams params, uint16_t sequenceCount) : TcBase(params, apid::TC_CAM_CMD_SEND, sequenceCount) {} protected: diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 2b335b66..d8c0d515 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -281,7 +281,7 @@ static const uint32_t UPDATE_STATUS_REPORT = 70000; /** * @brief This class creates a space packet containing only the header data and the CRC. */ -class ApidOnlyPacket : public SpacePacketBase { +class ApidOnlyPacket : public ploc::SpTcBase { public: /** * @brief Constructor @@ -290,7 +290,7 @@ class ApidOnlyPacket : public SpacePacketBase { * * @note Sequence count of empty packet is always 1. */ - ApidOnlyPacket(SpBaseParams params, uint16_t apid) : SpacePacketBase(params) { + ApidOnlyPacket(ploc::SpTcParams params, uint16_t apid) : ploc::SpTcBase(params) { spParams.setDataFieldLen(LENGTH_EMPTY_TC); spParams.creator.setApid(apid); } @@ -310,7 +310,7 @@ class ApidOnlyPacket : public SpacePacketBase { * @brief This class can be used to generate the space packet selecting the boot image of * of the MPSoC. */ -class MPSoCBootSelect : public SpacePacketBase { +class MPSoCBootSelect : public ploc::SpTcBase { public: static const uint8_t NVM0 = 0; static const uint8_t NVM1 = 1; @@ -325,7 +325,7 @@ class MPSoCBootSelect : public SpacePacketBase { * * @note Selection of partitions is currently not supported. */ - MPSoCBootSelect(SpBaseParams params) : SpacePacketBase(params) { + MPSoCBootSelect(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SEL_MPSOC_BOOT_IMAGE); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -361,7 +361,7 @@ class MPSoCBootSelect : public SpacePacketBase { * @brief This class creates the command to enable or disable the NVMs connected to the * supervisor. */ -class EnableNvms : public SpacePacketBase { +class EnableNvms : public ploc::SpTcBase { public: /** * @brief Constructor @@ -371,7 +371,7 @@ class EnableNvms : public SpacePacketBase { * @param bp1 Partition pin 1 * @param bp2 Partition pin 2 */ - EnableNvms(SpBaseParams params) : SpacePacketBase(params) { + EnableNvms(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_ENABLE_NVMS); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -399,9 +399,9 @@ class EnableNvms : public SpacePacketBase { /** * @brief This class generates the space packet to update the time of the PLOC supervisor. */ -class SetTimeRef : public SpacePacketBase { +class SetTimeRef : public ploc::SpTcBase { public: - SetTimeRef(SpBaseParams params) : SpacePacketBase(params) { + SetTimeRef(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_TIME_REF); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -457,14 +457,14 @@ class SetTimeRef : public SpacePacketBase { /** * @brief This class can be used to generate the set boot timout command. */ -class SetBootTimeout : public SpacePacketBase { +class SetBootTimeout : public ploc::SpTcBase { public: /** * @brief Constructor * * @param timeout The boot timeout in milliseconds. */ - SetBootTimeout(SpBaseParams params) : SpacePacketBase(params) { + SetBootTimeout(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_BOOT_TIMEOUT); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -494,14 +494,14 @@ class SetBootTimeout : public SpacePacketBase { /** * @brief This class can be used to generate the space packet to set the maximum boot tries. */ -class SetRestartTries : public SpacePacketBase { +class SetRestartTries : public ploc::SpTcBase { public: /** * @brief Constructor * * @param restartTries Maximum restart tries to set. */ - SetRestartTries(SpBaseParams params) : SpacePacketBase(params) { + SetRestartTries(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_MAX_RESTART_TRIES); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -530,12 +530,12 @@ class SetRestartTries : public SpacePacketBase { * of housekeeping data. Normally, this will be disabled by default. However, adding this * command can be useful for debugging. */ -class DisablePeriodicHkTransmission : public SpacePacketBase { +class DisablePeriodicHkTransmission : public ploc::SpTcBase { public: /** * @brief Constructor */ - DisablePeriodicHkTransmission(SpBaseParams params) : SpacePacketBase(params) { + DisablePeriodicHkTransmission(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_DISABLE_HK); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -562,7 +562,7 @@ class DisablePeriodicHkTransmission : public SpacePacketBase { * * @details There are 7 different latchup alerts. */ -class LatchupAlert : public SpacePacketBase { +class LatchupAlert : public ploc::SpTcBase { public: /** * @brief Constructor @@ -571,7 +571,7 @@ class LatchupAlert : public SpacePacketBase { * @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(SpBaseParams params) : SpacePacketBase(params) { + LatchupAlert(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -600,7 +600,7 @@ class LatchupAlert : public SpacePacketBase { void initPacket(uint8_t latchupId) { payloadStart[0] = latchupId; } }; -class SetAlertlimit : public SpacePacketBase { +class SetAlertlimit : public ploc::SpTcBase { public: /** * @brief Constructor @@ -609,7 +609,7 @@ class SetAlertlimit : public SpacePacketBase { * 3 - 3.3V, 4 - NVM_4XO, 5 - MISSION, 6 - SAFECOTS) * @param dutycycle */ - SetAlertlimit(SpBaseParams params) : SpacePacketBase(params) { + SetAlertlimit(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ALERT_LIMIT); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -645,14 +645,14 @@ class SetAlertlimit : public SpacePacketBase { /** * @brief This class packages the space packet to enable or disable ADC channels. */ -class SetAdcEnabledChannels : public SpacePacketBase { +class SetAdcEnabledChannels : public ploc::SpTcBase { public: /** * @brief Constructor * * @param ch Defines channels to be enabled or disabled. */ - SetAdcEnabledChannels(SpBaseParams params) : SpacePacketBase(params) { + SetAdcEnabledChannels(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ADC_ENABLED_CHANNELS); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -683,7 +683,7 @@ class SetAdcEnabledChannels : public SpacePacketBase { * @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 SpacePacketBase { +class SetAdcWindowAndStride : public ploc::SpTcBase { public: /** * @brief Constructor @@ -691,7 +691,7 @@ class SetAdcWindowAndStride : public SpacePacketBase { * @param windowSize * @param stridingStepSize */ - SetAdcWindowAndStride(SpBaseParams params) : SpacePacketBase(params) { + SetAdcWindowAndStride(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ADC_WINDOW_AND_STRIDE); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -724,14 +724,14 @@ class SetAdcWindowAndStride : public SpacePacketBase { /** * @brief This class packages the space packet to set the ADC trigger threshold. */ -class SetAdcThreshold : public SpacePacketBase { +class SetAdcThreshold : public ploc::SpTcBase { public: /** * @brief Constructor * * @param threshold */ - SetAdcThreshold(SpBaseParams params) : SpacePacketBase(params) { + SetAdcThreshold(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_ADC_THRESHOLD); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -762,14 +762,14 @@ class SetAdcThreshold : public SpacePacketBase { /** * @brief This class packages the space packet to run auto EM tests. */ -class RunAutoEmTests : public SpacePacketBase { +class RunAutoEmTests : public ploc::SpTcBase { public: /** * @brief Constructor * * @param test 1 - complete EM test, 2 - Short test (only memory readback NVM0,1,3) */ - RunAutoEmTests(SpBaseParams params) : SpacePacketBase(params) { + RunAutoEmTests(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_RUN_AUTO_EM_TESTS); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -798,7 +798,7 @@ class RunAutoEmTests : public SpacePacketBase { /** * @brief This class packages the space packet to wipe or dump parts of the MRAM. */ -class MramCmd : public SpacePacketBase { +class MramCmd : public ploc::SpTcBase { public: enum class MramAction { WIPE, DUMP }; @@ -811,7 +811,7 @@ class MramCmd : public SpacePacketBase { * * @note The content at the stop address is excluded from the dump or wipe operation. */ - MramCmd(SpBaseParams params) : SpacePacketBase(params) { + MramCmd(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -856,7 +856,7 @@ class MramCmd : public SpacePacketBase { * @brief This class packages the space packet change the state of a GPIO. This command is only * required for ground testing. */ -class SetGpio : public SpacePacketBase { +class SetGpio : public ploc::SpTcBase { public: /** * @brief Constructor @@ -865,7 +865,7 @@ class SetGpio : public SpacePacketBase { * @param pin * @param val */ - SetGpio(SpBaseParams params) : SpacePacketBase(params) { + SetGpio(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_SET_GPIO); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -901,7 +901,7 @@ class SetGpio : public SpacePacketBase { * @brief This class packages the space packet causing the supervisor print the state of a GPIO * to the debug output. */ -class ReadGpio : public SpacePacketBase { +class ReadGpio : public ploc::SpTcBase { public: /** * @brief Constructor @@ -909,7 +909,7 @@ class ReadGpio : public SpacePacketBase { * @param port * @param pin */ - ReadGpio(SpBaseParams params) : SpacePacketBase(params) { + ReadGpio(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setDataFieldLen(DATA_FIELD_LENGTH); spParams.creator.setApid(APID_READ_GPIO); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -947,7 +947,7 @@ class ReadGpio : public SpacePacketBase { * OP = 0x01: Only the mirror entries will be wiped. * OP = 0x02: Only the circular entries will be wiped. */ -class FactoryReset : public SpacePacketBase { +class FactoryReset : public ploc::SpTcBase { public: enum class Op { CLEAR_ALL, MIRROR_ENTRIES, CIRCULAR_ENTRIES }; @@ -956,7 +956,7 @@ class FactoryReset : public SpacePacketBase { * * @param op */ - FactoryReset(SpBaseParams params) : SpacePacketBase(params) { + FactoryReset(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.creator.setApid(APID_FACTORY_RESET); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -991,38 +991,9 @@ class FactoryReset : public SpacePacketBase { } }; -// class SupvTcSpacePacket : public SpacePacketBase { -// public: -// /** -// * @brief Constructor -// * -// * @param payloadDataLen Length of data field without CRC -// */ -// SupvTcSpacePacket(SpBaseParams params): SpacePacketBase(params) { -// spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); -// } -// -// ReturnValue_t buildPacket(uint16_t payloadDataLenWithoutCrc, uint16_t apid) { -// spParams.setPayloadLen(payloadDataLenWithoutCrc + 2); -// spParams.creator.setApid(apid); -// auto res = checkSizeAndSerializeHeader(); -// if(res != result::OK) { -// return res; -// } -// return calcCrc(); -// } -// -// private: -// // The sequence count of most of the TC packets for the supervisor is 1. -// static const uint16_t DEFAULT_SEQUENCE_COUNT = 1; -// -// // The size of the payload data (data field without crc size) -// size_t payloadDataLen = 0; -// }; - -class SetShutdownTimeout : public SpacePacketBase { +class SetShutdownTimeout : public ploc::SpTcBase { public: - SetShutdownTimeout(SpBaseParams params) : SpacePacketBase(params) { + SetShutdownTimeout(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setPayloadLen(PAYLOAD_LEN); spParams.creator.setApid(APID_SET_SHUTDOWN_TIMEOUT); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -1052,7 +1023,7 @@ class SetShutdownTimeout : public SpacePacketBase { /** * @brief Command to request CRC over memory region of the supervisor. */ -class CheckMemory : public SpacePacketBase { +class CheckMemory : public ploc::SpTcBase { public: /** * @brief Constructor @@ -1061,7 +1032,7 @@ class CheckMemory : public SpacePacketBase { * @param startAddress Start address of CRC calculation * @param length Length in bytes of memory region */ - CheckMemory(SpBaseParams params) : SpacePacketBase(params) { + CheckMemory(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setPayloadLen(PAYLOAD_LENGTH); spParams.creator.setApid(APID_CHECK_MEMORY); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -1100,7 +1071,7 @@ class CheckMemory : public SpacePacketBase { /** * @brief This class packages the space packet transporting a part of an MPSoC update. */ -class WriteMemory : public SpacePacketBase { +class WriteMemory : public ploc::SpTcBase { public: /** * @brief Constructor @@ -1109,7 +1080,7 @@ class WriteMemory : public SpacePacketBase { * @param sequenceCount Sequence count (first update packet expects 1 as sequence count) * @param updateData Pointer to buffer containing update data */ - WriteMemory(SpBaseParams params) : SpacePacketBase(params) { + WriteMemory(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.creator.setApid(APID_WRITE_MEMORY); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); } @@ -1164,9 +1135,9 @@ class WriteMemory : public SpacePacketBase { /** * @brief This class can be used to package the update available or update verify command. */ -class EraseMemory : public SpacePacketBase { +class EraseMemory : public ploc::SpTcBase { public: - EraseMemory(SpBaseParams params) : SpacePacketBase(params) { + EraseMemory(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setPayloadLen(PAYLOAD_LENGTH); spParams.creator.setApid(APID_ERASE_MEMORY); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -1208,9 +1179,9 @@ class EraseMemory : public SpacePacketBase { /** * @brief This class creates the space packet to enable the auto TM generation */ -class EnableAutoTm : public SpacePacketBase { +class EnableAutoTm : public ploc::SpTcBase { public: - EnableAutoTm(SpBaseParams params) : SpacePacketBase(params) { + EnableAutoTm(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setPayloadLen(PAYLOAD_LENGTH); spParams.creator.setApid(APID_AUTO_TM); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -1233,9 +1204,9 @@ class EnableAutoTm : public SpacePacketBase { /** * @brief This class creates the space packet to disable the auto TM generation */ -class DisableAutoTm : public SpacePacketBase { +class DisableAutoTm : public ploc::SpTcBase { public: - DisableAutoTm(SpBaseParams params) : SpacePacketBase(params) { + DisableAutoTm(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setPayloadLen(PAYLOAD_LENGTH); spParams.creator.setApid(APID_AUTO_TM); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -1258,7 +1229,7 @@ class DisableAutoTm : public SpacePacketBase { /** * @brief This class creates the space packet to request the logging data from the supervisor */ -class RequestLoggingData : public SpacePacketBase { +class RequestLoggingData : public ploc::SpTcBase { public: enum class Sa : uint8_t { REQUEST_COUNTERS = 1, @@ -1267,7 +1238,7 @@ class RequestLoggingData : public SpacePacketBase { SET_LOGGING_TOPIC = 4 }; - RequestLoggingData(SpBaseParams params) : SpacePacketBase(params) { + RequestLoggingData(ploc::SpTcParams params) : ploc::SpTcBase(params) { spParams.setPayloadLen(PAYLOAD_LENGTH); spParams.creator.setApid(APID_REQUEST_LOGGING_DATA); spParams.creator.setSeqCount(DEFAULT_SEQUENCE_COUNT); @@ -1288,47 +1259,9 @@ class RequestLoggingData : public SpacePacketBase { static const uint8_t TPC_OFFSET = 1; }; -/** - * @brief Class for handling tm replies of the supervisor. - */ -class TmPacket : public SpacePacketReader { +class VerificationReport : public ploc::SpTmReader { public: - TmPacket() = default; - /** - * @brief Constructor creates idle packet and sets length field to maximum allowed size. - */ - TmPacket(const uint8_t* buf, size_t maxSize) : SpacePacketReader(buf, maxSize) {} - - ReturnValue_t setData(const uint8_t* buf, size_t maxSize) { - return setReadOnlyData(buf, maxSize); - } - - ReturnValue_t check() { - if (isNull()) { - return HasReturnvaluesIF::RETURN_FAILED; - } - return checkSize(); - } - - /** - * @brief Returns the payload data length (data field length without CRC) - */ - uint16_t getPayloadDataLength() { return getPacketDataLen() - 2; } - - ReturnValue_t checkCrc() { - const uint8_t* crcPtr = getFullData() + getFullPacketLen() - CRC_SIZE; - uint16_t receivedCrc = *(crcPtr) << 8 | *(crcPtr + 1); - uint16_t recalculatedCrc = CRC::crc16ccitt(getFullData(), getFullPacketLen() - CRC_SIZE); - if (recalculatedCrc != receivedCrc) { - return SupvReturnValuesIF::CRC_FAILURE; - } - return HasReturnvaluesIF::RETURN_OK; - } -}; - -class VerificationReport : public TmPacket { - public: - VerificationReport(const uint8_t* buf, size_t maxSize) : TmPacket(buf, maxSize) {} + VerificationReport(const uint8_t* buf, size_t maxSize) : ploc::SpTmReader(buf, maxSize) {} /** * @brief Gets the APID of command which caused the transmission of this verification report. @@ -1870,10 +1803,10 @@ class LoggingReport : public StaticLocalDataSet { } }; -class UpdateStatusReport : public TmPacket { +class UpdateStatusReport : public ploc::SpTmReader { public: UpdateStatusReport() = default; - UpdateStatusReport(const uint8_t* buf, size_t maxSize) : TmPacket(buf, maxSize) {} + UpdateStatusReport(const uint8_t* buf, size_t maxSize) : ploc::SpTmReader(buf, maxSize) {} ReturnValue_t parseDataField() { ReturnValue_t result = lengthCheck(); diff --git a/linux/devices/ploc/PlocMPSoCHandler.cpp b/linux/devices/ploc/PlocMPSoCHandler.cpp index 238c8178..9df54ed2 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.cpp +++ b/linux/devices/ploc/PlocMPSoCHandler.cpp @@ -673,12 +673,11 @@ ReturnValue_t PlocMPSoCHandler::handleMemoryReadReport(const uint8_t* data) { ReturnValue_t PlocMPSoCHandler::handleCamCmdRpt(const uint8_t* data) { ReturnValue_t result = RETURN_OK; - SpacePacket packet; - std::memcpy(packet.getWholeData(), data, tmCamCmdRpt.rememberSpacePacketSize); result = verifyPacket(data, tmCamCmdRpt.rememberSpacePacketSize); if (result == MPSoCReturnValuesIF::CRC_FAILURE) { sif::warning << "PlocMPSoCHandler::handleCamCmdRpt: CRC failure" << std::endl; } + SpacePacketReader packetReader(data, tmCamCmdRpt.rememberSpacePacketSize); const uint8_t* dataFieldPtr = data + mpsoc::SPACE_PACKET_HEADER_SIZE + sizeof(uint16_t); std::string camCmdRptMsg( reinterpret_cast(dataFieldPtr), @@ -689,8 +688,8 @@ ReturnValue_t PlocMPSoCHandler::handleCamCmdRpt(const uint8_t* data) { sif::info << "PlocMPSoCHandler: CamCmdRpt Ack value: 0x" << std::hex << static_cast(ackValue) << std::endl; #endif /* OBSW_DEBUG_PLOC_MPSOC == 1 */ - handleDeviceTM(packet.getPacketData() + sizeof(uint16_t), packet.getPacketDataLength() - 1, - mpsoc::TM_CAM_CMD_RPT); + handleDeviceTM(packetReader.getPacketData() + sizeof(uint16_t), + packetReader.getPacketDataLen() - 1, mpsoc::TM_CAM_CMD_RPT); return result; } diff --git a/linux/devices/ploc/PlocMPSoCHandler.h b/linux/devices/ploc/PlocMPSoCHandler.h index da3e1744..4325f8ee 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.h +++ b/linux/devices/ploc/PlocMPSoCHandler.h @@ -113,6 +113,8 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF { SourceSequenceCounter sequenceCount = SourceSequenceCounter(ccsds::LIMIT_SEQUENCE_COUNT - 1); uint8_t commandBuffer[mpsoc::MAX_COMMAND_SIZE]; + SpacePacketCreator creator; + ploc::SpTcParams spParams = ploc::SpTcParams(creator); /** * This variable is used to store the id of the next reply to receive. This is necessary @@ -151,9 +153,6 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF { TelemetryBuffer tmBuffer; - SpacePacketCreator creator; - SpBaseParams spParams = SpBaseParams(creator); - enum class PowerState { OFF, BOOTING, SHUTDOWN, ON }; PowerState powerState = PowerState::OFF; diff --git a/linux/devices/ploc/PlocMPSoCHelper.cpp b/linux/devices/ploc/PlocMPSoCHelper.cpp index 5e6da78b..9156138e 100644 --- a/linux/devices/ploc/PlocMPSoCHelper.cpp +++ b/linux/devices/ploc/PlocMPSoCHelper.cpp @@ -10,7 +10,12 @@ #include "mission/utility/Timestamp.h" -PlocMPSoCHelper::PlocMPSoCHelper(object_id_t objectId) : SystemObject(objectId) {} +using namespace ploc; + +PlocMPSoCHelper::PlocMPSoCHelper(object_id_t objectId) : SystemObject(objectId) { + spParams.buf = commandBuffer; + spParams.maxSize = sizeof(commandBuffer); +} PlocMPSoCHelper::~PlocMPSoCHelper() {} @@ -138,8 +143,11 @@ ReturnValue_t PlocMPSoCHelper::performFlashWrite() { return FILE_CLOSED_ACCIDENTALLY; } (*sequenceCount)++; - mpsoc::TcFlashWrite tc(*sequenceCount); - tc.createPacket(tempData, dataLength); + mpsoc::TcFlashWrite tc(spParams, *sequenceCount); + result = tc.buildPacket(tempData, dataLength); + if (result != RETURN_OK) { + return result; + } result = handlePacketTransmission(tc); if (result != RETURN_OK) { return result; @@ -155,7 +163,7 @@ ReturnValue_t PlocMPSoCHelper::performFlashWrite() { ReturnValue_t PlocMPSoCHelper::flashfopen() { ReturnValue_t result = RETURN_OK; (*sequenceCount)++; - mpsoc::FlashFopen flashFopen(*sequenceCount); + mpsoc::FlashFopen flashFopen(spParams, *sequenceCount); result = flashFopen.createPacket(flashWrite.mpsocFile, mpsoc::FlashFopen::APPEND); if (result != RETURN_OK) { return result; @@ -170,7 +178,7 @@ ReturnValue_t PlocMPSoCHelper::flashfopen() { ReturnValue_t PlocMPSoCHelper::flashfclose() { ReturnValue_t result = RETURN_OK; (*sequenceCount)++; - mpsoc::FlashFclose flashFclose(*sequenceCount); + mpsoc::FlashFclose flashFclose(spParams, *sequenceCount); result = flashFclose.createPacket(flashWrite.mpsocFile); if (result != RETURN_OK) { return result; @@ -182,7 +190,7 @@ ReturnValue_t PlocMPSoCHelper::flashfclose() { return RETURN_OK; } -ReturnValue_t PlocMPSoCHelper::handlePacketTransmission(mpsoc::TcBase& tc) { +ReturnValue_t PlocMPSoCHelper::handlePacketTransmission(ploc::SpTcBase& tc) { ReturnValue_t result = RETURN_OK; result = sendCommand(tc); if (result != RETURN_OK) { @@ -199,9 +207,9 @@ ReturnValue_t PlocMPSoCHelper::handlePacketTransmission(mpsoc::TcBase& tc) { return RETURN_OK; } -ReturnValue_t PlocMPSoCHelper::sendCommand(mpsoc::TcBase& tc) { +ReturnValue_t PlocMPSoCHelper::sendCommand(ploc::SpTcBase& tc) { ReturnValue_t result = RETURN_OK; - result = uartComIF->sendMessage(comCookie, tc.getWholeData(), tc.getFullSize()); + result = uartComIF->sendMessage(comCookie, tc.getFullPacket(), tc.getFullPacketLen()); if (result != RETURN_OK) { sif::warning << "PlocMPSoCHelper::sendCommand: Failed to send command" << std::endl; triggerEvent(MPSOC_SENDING_COMMAND_FAILED, result, static_cast(internalState)); @@ -212,12 +220,16 @@ ReturnValue_t PlocMPSoCHelper::sendCommand(mpsoc::TcBase& tc) { ReturnValue_t PlocMPSoCHelper::handleAck() { ReturnValue_t result = RETURN_OK; - mpsoc::TmPacket tmPacket; - result = handleTmReception(&tmPacket, mpsoc::SIZE_ACK_REPORT); + result = handleTmReception(mpsoc::SIZE_ACK_REPORT); if (result != RETURN_OK) { return result; } - uint16_t apid = tmPacket.getAPID(); + SpTmReader tmPacket(tmBuf.data(), tmBuf.size()); + result = checkReceivedTm(tmPacket); + if (result != RETURN_OK) { + return result; + } + uint16_t apid = tmPacket.getApid(); if (apid != mpsoc::apid::ACK_SUCCESS) { handleAckApidFailure(apid); return RETURN_FAILED; @@ -239,12 +251,17 @@ void PlocMPSoCHelper::handleAckApidFailure(uint16_t apid) { ReturnValue_t PlocMPSoCHelper::handleExe() { ReturnValue_t result = RETURN_OK; - mpsoc::TmPacket tmPacket; - result = handleTmReception(&tmPacket, mpsoc::SIZE_EXE_REPORT); + + result = handleTmReception(mpsoc::SIZE_EXE_REPORT); if (result != RETURN_OK) { return result; } - uint16_t apid = tmPacket.getAPID(); + ploc::SpTmReader tmPacket(tmBuf.data(), tmBuf.size()); + result = checkReceivedTm(tmPacket); + if (result != RETURN_OK) { + return result; + } + uint16_t apid = tmPacket.getApid(); if (apid != mpsoc::apid::EXE_SUCCESS) { handleExeApidFailure(apid); return RETURN_FAILED; @@ -264,12 +281,12 @@ void PlocMPSoCHelper::handleExeApidFailure(uint16_t apid) { } } -ReturnValue_t PlocMPSoCHelper::handleTmReception(mpsoc::TmPacket* tmPacket, size_t remainingBytes) { +ReturnValue_t PlocMPSoCHelper::handleTmReception(size_t remainingBytes) { ReturnValue_t result = RETURN_OK; size_t readBytes = 0; size_t currentBytes = 0; for (int retries = 0; retries < RETRIES; retries++) { - result = receive(tmPacket->getWholeData() + readBytes, ¤tBytes, remainingBytes); + result = receive(tmBuf.data() + readBytes, ¤tBytes, remainingBytes); if (result != RETURN_OK) { return result; } @@ -284,18 +301,30 @@ ReturnValue_t PlocMPSoCHelper::handleTmReception(mpsoc::TmPacket* tmPacket, size triggerEvent(MPSOC_MISSING_EXE, remainingBytes, static_cast(internalState)); return RETURN_FAILED; } - result = tmPacket->checkCrc(); + return result; +} + +ReturnValue_t PlocMPSoCHelper::checkReceivedTm(SpTmReader& reader) { + ReturnValue_t result = reader.checkSize(); + if (result != RETURN_OK) { + sif::error << "PlocMPSoCHelper::handleTmReception: Size check on received TM failed" + << std::endl; + triggerEvent(MPSOC_TM_SIZE_ERROR); + return result; + } + reader.checkCrc(); if (result != RETURN_OK) { sif::warning << "PlocMPSoCHelper::handleTmReception: CRC check failed" << std::endl; + triggerEvent(MPSOC_TM_CRC_MISSMATCH, *sequenceCount); return result; } (*sequenceCount)++; - uint16_t recvSeqCnt = tmPacket->getPacketSequenceCount(); + uint16_t recvSeqCnt = reader.getSequenceCount(); if (recvSeqCnt != *sequenceCount) { triggerEvent(MPSOC_HELPER_SEQ_CNT_MISMATCH, *sequenceCount, recvSeqCnt); *sequenceCount = recvSeqCnt; } - return result; + return RETURN_OK; } ReturnValue_t PlocMPSoCHelper::receive(uint8_t* data, size_t* readBytes, size_t requestBytes) { diff --git a/linux/devices/ploc/PlocMPSoCHelper.h b/linux/devices/ploc/PlocMPSoCHelper.h index 3c011b6a..eb5b4346 100644 --- a/linux/devices/ploc/PlocMPSoCHelper.h +++ b/linux/devices/ploc/PlocMPSoCHelper.h @@ -67,6 +67,8 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF, public H //! P1: Expected sequence count //! P2: Received sequence count static const Event MPSOC_HELPER_SEQ_CNT_MISMATCH = MAKE_EVENT(11, severity::LOW); + static const Event MPSOC_TM_SIZE_ERROR = MAKE_EVENT(12, severity::LOW); + static const Event MPSOC_TM_CRC_MISSMATCH = MAKE_EVENT(13, severity::LOW); PlocMPSoCHelper(object_id_t objectId); virtual ~PlocMPSoCHelper(); @@ -123,6 +125,10 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF, public H SdCardManager* sdcMan = nullptr; #endif uint8_t commandBuffer[mpsoc::MAX_COMMAND_SIZE]; + SpacePacketCreator creator; + ploc::SpTcParams spParams = ploc::SpTcParams(creator); + + std::array tmBuf; bool terminate = false; @@ -134,20 +140,21 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF, public H // Communication cookie. Must be set by the MPSoC Handler CookieIF* comCookie = nullptr; // Sequence count, must be set by Ploc MPSoC Handler - SourceSequenceCounter* sequenceCount; + SourceSequenceCounter* sequenceCount = nullptr; ReturnValue_t resetHelper(); ReturnValue_t performFlashWrite(); ReturnValue_t flashfopen(); ReturnValue_t flashfclose(); - ReturnValue_t handlePacketTransmission(mpsoc::TcBase& tc); - ReturnValue_t sendCommand(mpsoc::TcBase& tc); + ReturnValue_t handlePacketTransmission(ploc::SpTcBase& tc); + ReturnValue_t sendCommand(ploc::SpTcBase& tc); ReturnValue_t receive(uint8_t* data, size_t* readBytes, size_t requestBytes); ReturnValue_t handleAck(); ReturnValue_t handleExe(); void handleAckApidFailure(uint16_t apid); void handleExeApidFailure(uint16_t apid); - ReturnValue_t handleTmReception(mpsoc::TmPacket* tmPacket, size_t remainingBytes); + ReturnValue_t handleTmReception(size_t remainingBytes); + ReturnValue_t checkReceivedTm(ploc::SpTmReader& reader); }; #endif /* BSP_Q7S_DEVICES_PLOCMPSOCHELPER_H_ */ diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 26579caa..2b6c44d3 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -906,8 +906,8 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) { using namespace supv; ReturnValue_t result = RETURN_OK; - AcknowledgmentReport ack; - ack.addWholeData(data, SIZE_ACK_REPORT); + AcknowledgmentReport ack(data, SIZE_ACK_REPORT); + // ack.addWholeData(data, SIZE_ACK_REPORT); result = ack.checkCrc(); if (result != RETURN_OK) { @@ -960,8 +960,14 @@ ReturnValue_t PlocSupervisorHandler::handleExecutionReport(const uint8_t* data) using namespace supv; ReturnValue_t result = RETURN_OK; - ExecutionReport exe; - exe.addWholeData(data, SIZE_EXE_REPORT); + ExecutionReport exe(data, SIZE_EXE_REPORT); + if (exe.isNull()) { + return RETURN_FAILED; + } + result = exe.checkSize(); + if (result != RETURN_OK) { + return result; + } result = exe.checkCrc(); if (result != RETURN_OK) { @@ -2018,24 +2024,30 @@ ReturnValue_t PlocSupervisorHandler::eventSubscription() { return result; } -void PlocSupervisorHandler::handleExecutionSuccessReport(const uint8_t* data) { +ReturnValue_t PlocSupervisorHandler::handleExecutionSuccessReport(const uint8_t* data) { DeviceCommandId_t commandId = getPendingCommand(); switch (commandId) { case supv::READ_GPIO: { - supv::ExecutionReport exe; - exe.addWholeData(data, supv::SIZE_EXE_REPORT); + supv::ExecutionReport exe(data, supv::SIZE_EXE_REPORT); + if (exe.isNull()) { + return RETURN_FAILED; + } + ReturnValue_t result = exe.checkSize(); + if (result != RETURN_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; + return RETURN_OK; } uint8_t data[sizeof(gpioState)]; size_t size = 0; - ReturnValue_t result = SerializeAdapter::serialize(&gpioState, data, &size, sizeof(gpioState), - SerializeIF::Endianness::BIG); + result = SerializeAdapter::serialize(&gpioState, data, &size, sizeof(gpioState), + SerializeIF::Endianness::BIG); if (result != RETURN_OK) { sif::debug << "PlocSupervisorHandler: Failed to deserialize GPIO state" << std::endl; } @@ -2054,6 +2066,7 @@ void PlocSupervisorHandler::handleExecutionSuccessReport(const uint8_t* data) { default: break; } + return RETURN_OK; } void PlocSupervisorHandler::handleExecutionFailureReport(uint16_t statusCode) { diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index ec40cfad..c6476679 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -101,7 +101,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]; SpacePacketCreator creator; - SpBaseParams spParams = SpBaseParams(creator); + ploc::SpTcParams spParams = ploc::SpTcParams(creator); /** * This variable is used to store the id of the next reply to receive. This is necessary @@ -371,7 +371,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { uint8_t* memoryId, uint32_t* startAddress); ReturnValue_t eventSubscription(); - void handleExecutionSuccessReport(const uint8_t* data); + ReturnValue_t handleExecutionSuccessReport(const uint8_t* data); void handleExecutionFailureReport(uint16_t statusCode); void printAckFailureInfo(uint16_t statusCode, DeviceCommandId_t commandId); diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 1c93e7ad..c9dc12a8 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -334,7 +334,7 @@ ReturnValue_t PlocSupvHelper::eraseMemory() { return RETURN_OK; } -ReturnValue_t PlocSupvHelper::handlePacketTransmission(SpacePacketBase& packet, +ReturnValue_t PlocSupvHelper::handlePacketTransmission(ploc::SpTcBase& packet, uint32_t timeoutExecutionReport) { ReturnValue_t result = RETURN_OK; result = sendCommand(packet); @@ -352,7 +352,7 @@ ReturnValue_t PlocSupvHelper::handlePacketTransmission(SpacePacketBase& packet, return RETURN_OK; } -ReturnValue_t PlocSupvHelper::sendCommand(SpacePacketBase& packet) { +ReturnValue_t PlocSupvHelper::sendCommand(ploc::SpTcBase& packet) { ReturnValue_t result = RETURN_OK; rememberApid = packet.getApid(); result = uartComIF->sendMessage(comCookie, packet.getFullPacket(), packet.getFullPacketLen()); @@ -366,14 +366,20 @@ ReturnValue_t PlocSupvHelper::sendCommand(SpacePacketBase& packet) { ReturnValue_t PlocSupvHelper::handleAck() { ReturnValue_t result = RETURN_OK; - supv::AcknowledgmentReport ackReport; - result = handleTmReception(&ackReport, supv::SIZE_ACK_REPORT); + + result = handleTmReception(supv::SIZE_ACK_REPORT); if (result != RETURN_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 = ackReport.checkCrc(); + if (result != RETURN_OK) { + triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); + return result; + } result = ackReport.checkApid(); if (result != RETURN_OK) { if (result == SupvReturnValuesIF::RECEIVED_ACK_FAILURE) { @@ -388,14 +394,20 @@ ReturnValue_t PlocSupvHelper::handleAck() { ReturnValue_t PlocSupvHelper::handleExe(uint32_t timeout) { ReturnValue_t result = RETURN_OK; - supv::ExecutionReport exeReport; - result = handleTmReception(&exeReport, supv::SIZE_EXE_REPORT, timeout); + + result = handleTmReception(supv::SIZE_EXE_REPORT, timeout); if (result != RETURN_OK) { triggerEvent(EXE_RECEPTION_FAILURE, result, static_cast(rememberApid)); sif::warning << "PlocSupvHelper::handleExe: Error in reception of execution report" << std::endl; return result; } + supv::ExecutionReport exeReport(tmBuf.data(), tmBuf.size()); + result = exeReport.checkCrc(); + if (result != RETURN_OK) { + triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); + return result; + } result = exeReport.checkApid(); if (result != RETURN_OK) { if (result == SupvReturnValuesIF::RECEIVED_EXE_FAILURE) { @@ -408,14 +420,13 @@ ReturnValue_t PlocSupvHelper::handleExe(uint32_t timeout) { return RETURN_OK; } -ReturnValue_t PlocSupvHelper::handleTmReception(supv::TmPacket* tmPacket, size_t remainingBytes, - uint32_t timeout) { +ReturnValue_t PlocSupvHelper::handleTmReception(size_t remainingBytes, uint32_t timeout) { ReturnValue_t result = RETURN_OK; size_t readBytes = 0; size_t currentBytes = 0; Countdown countdown(timeout); while (!countdown.hasTimedOut()) { - result = receive(tmPacket->getWholeData() + readBytes, ¤tBytes, remainingBytes); + result = receive(tmBuf.data() + readBytes, ¤tBytes, remainingBytes); if (result != RETURN_OK) { return result; } @@ -430,11 +441,6 @@ ReturnValue_t PlocSupvHelper::handleTmReception(supv::TmPacket* tmPacket, size_t << remainingBytes << " bytes" << std::endl; return RETURN_FAILED; } - result = tmPacket->checkCrc(); - if (result != RETURN_OK) { - sif::warning << "PlocSupvHelper::handleTmReception: CRC check failed" << std::endl; - return result; - } return result; } @@ -512,10 +518,14 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { if (result != RETURN_OK) { return result; } - supv::UpdateStatusReport updateStatusReport; - result = handleTmReception(&updateStatusReport, - static_cast(updateStatusReport.getNominalSize()), + supv::UpdateStatusReport updateStatusReport(tmBuf.data(), tmBuf.size()); + result = handleTmReception(static_cast(updateStatusReport.getNominalSize()), supv::recv_timeout::UPDATE_STATUS_REPORT); + result = updateStatusReport.checkCrc(); + if (result != RETURN_OK) { + sif::warning << "PlocSupvHelper::handleTmReception: CRC check failed" << std::endl; + return result; + } if (result != RETURN_OK) { sif::warning << "PlocSupvHelper::handleCheckMemoryCommand: Failed to receive update status report" @@ -555,7 +565,7 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception() { std::ofstream file(filename, std::ios_base::app | std::ios_base::out); uint32_t packetsRead = 0; size_t requestLen = 0; - supv::TmPacket tmPacket; + ploc::SpTmReader tmReader(tmBuf.data(), tmBuf.size()); for (packetsRead = 0; packetsRead < NUM_EVENT_BUFFER_PACKETS; packetsRead++) { if (terminate) { triggerEvent(SUPV_EVENT_BUFFER_REQUEST_TERMINATED, packetsRead - 1); @@ -567,22 +577,27 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception() { } else { requestLen = SIZE_EVENT_BUFFER_FULL_PACKET; } - result = handleTmReception(&tmPacket, requestLen); + result = handleTmReception(requestLen); if (result != RETURN_OK) { sif::debug << "PlocSupvHelper::handleEventBufferReception: Failed while trying to read packet" << " " << packetsRead + 1 << std::endl; file.close(); return result; } - uint16_t apid = tmPacket.getApid(); + ReturnValue_t result = tmReader.checkCrc(); + if (result != RETURN_OK) { + triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); + return result; + } + uint16_t apid = tmReader.getApid(); if (apid != supv::APID_MRAM_DUMP_TM) { sif::warning << "PlocSupvHelper::handleEventBufferReception: Did not expect space packet " << "with APID 0x" << std::hex << apid << std::endl; file.close(); return EVENT_BUFFER_REPLY_INVALID_APID; } - file.write(reinterpret_cast(tmPacket.getPacketData()), - tmPacket.getPayloadDataLength()); + file.write(reinterpret_cast(tmReader.getPacketData()), + tmReader.getPayloadDataLength()); } return result; } diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 128b4774..4b0348c9 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -86,6 +86,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha //! [EXPORT] : [COMMENT] Update procedure failed when sending packet with number P1 //! P1: Packet number for which the memory write command fails static const Event WRITE_MEMORY_FAILED = MAKE_EVENT(19, severity::LOW); + static const Event SUPV_REPLY_CRC_MISSMATCH = MAKE_EVENT(20, severity::LOW); PlocSupvHelper(object_id_t objectId); virtual ~PlocSupvHelper(); @@ -178,7 +179,9 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha #endif uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]; SpacePacketCreator creator; - SpBaseParams spParams = SpBaseParams(creator); + ploc::SpTcParams spParams = ploc::SpTcParams(creator); + + std::array tmBuf; bool terminate = false; @@ -198,9 +201,9 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha ReturnValue_t continueUpdate(); ReturnValue_t writeUpdatePackets(); ReturnValue_t performEventBufferRequest(); - ReturnValue_t handlePacketTransmission(SpacePacketBase& packet, + ReturnValue_t handlePacketTransmission(ploc::SpTcBase& packet, uint32_t timeoutExecutionReport = 60000); - ReturnValue_t sendCommand(SpacePacketBase& packet); + ReturnValue_t sendCommand(ploc::SpTcBase& packet); /** * @brief Function which reads form the communication interface * @@ -221,8 +224,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha * @note It can take up to 70 seconds until the supervisor replies with an acknowledgment * failure report. */ - ReturnValue_t handleTmReception(supv::TmPacket* tmPacket, size_t remainingBytes, - uint32_t timeout = 70000); + ReturnValue_t handleTmReception(size_t remainingBytes, uint32_t timeout = 70000); ReturnValue_t selectMemory(); ReturnValue_t prepareUpdate(); ReturnValue_t eraseMemory(); diff --git a/mission/devices/devicedefinitions/SpBase.h b/mission/devices/devicedefinitions/SpBase.h index ba73904e..c03c7360 100644 --- a/mission/devices/devicedefinitions/SpBase.h +++ b/mission/devices/devicedefinitions/SpBase.h @@ -2,13 +2,16 @@ #define MISSION_DEVICES_DEVICEDEFINITIONS_SPBASE_H_ #include +#include #include -struct SpBaseParams { - SpBaseParams(SpacePacketCreator& creator) : creator(creator) {} +namespace ploc { - SpBaseParams(SpacePacketCreator& creator, uint8_t* buf, size_t maxSize) +struct SpTcParams { + SpTcParams(SpacePacketCreator& creator) : creator(creator) {} + + SpTcParams(SpacePacketCreator& creator, uint8_t* buf, size_t maxSize) : creator(creator), buf(buf), maxSize(maxSize) {} void setPayloadLen(size_t payloadLen_) { dataFieldLen = payloadLen_ + 2; } @@ -21,11 +24,11 @@ struct SpBaseParams { size_t dataFieldLen = 0; }; -class SpacePacketBase { +class SpTcBase { public: - SpacePacketBase(SpBaseParams params) : spParams(params) { updateFields(); } + SpTcBase(SpTcParams params) : spParams(params) { updateFields(); } - SpacePacketBase(SpBaseParams params, uint16_t apid, uint16_t seqCount) : spParams(params) { + SpTcBase(SpTcParams params, uint16_t apid, uint16_t seqCount) : spParams(params) { spParams.creator.setApid(apid); spParams.creator.setSeqCount(seqCount); updateFields(); @@ -76,8 +79,41 @@ class SpacePacketBase { } protected: - SpBaseParams spParams; + ploc::SpTcParams spParams; uint8_t* payloadStart; }; +/** + * @brief Class for handling tm replies of the supervisor. + */ +class SpTmReader : public SpacePacketReader { + public: + SpTmReader() = default; + /** + * @brief Constructor creates idle packet and sets length field to maximum allowed size. + */ + SpTmReader(const uint8_t* buf, size_t maxSize) : SpacePacketReader(buf, maxSize) {} + + ReturnValue_t setData(const uint8_t* buf, size_t maxSize) { + return setReadOnlyData(buf, maxSize); + } + + /** + * @brief Returns the payload data length (data field length without CRC) + */ + uint16_t getPayloadDataLength() { return getPacketDataLen() - 2; } + + ReturnValue_t checkCrc() { + const uint8_t* crcPtr = getFullData() + getFullPacketLen() - CRC_SIZE; + uint16_t receivedCrc = *(crcPtr) << 8 | *(crcPtr + 1); + uint16_t recalculatedCrc = CRC::crc16ccitt(getFullData(), getFullPacketLen() - CRC_SIZE); + if (recalculatedCrc != receivedCrc) { + return HasReturnvaluesIF::RETURN_FAILED; + } + return HasReturnvaluesIF::RETURN_OK; + } +}; + +} // namespace ploc + #endif /* MISSION_DEVICES_DEVICEDEFINITIONS_SPBASE_H_ */ From 458929957dea256397e1102491fcf893f7f610c9 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 15 Aug 2022 18:43:28 +0200 Subject: [PATCH 06/58] generic TM checker --- linux/devices/ploc/PlocSupvHelper.cpp | 26 +++++++++++++++++++------- linux/devices/ploc/PlocSupvHelper.h | 5 ++++- 2 files changed, 23 insertions(+), 8 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index c9dc12a8..54e7c8ba 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -375,9 +375,8 @@ ReturnValue_t PlocSupvHelper::handleAck() { return result; } supv::AcknowledgmentReport ackReport(tmBuf.data(), tmBuf.size()); - result = ackReport.checkCrc(); - if (result != RETURN_OK) { - triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); + result = checkReceivedTm(ackReport); + if(result != RETURN_OK) { return result; } result = ackReport.checkApid(); @@ -403,9 +402,8 @@ ReturnValue_t PlocSupvHelper::handleExe(uint32_t timeout) { return result; } supv::ExecutionReport exeReport(tmBuf.data(), tmBuf.size()); - result = exeReport.checkCrc(); - if (result != RETURN_OK) { - triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); + result = checkReceivedTm(exeReport); + if(result != RETURN_OK) { return result; } result = exeReport.checkApid(); @@ -444,6 +442,20 @@ ReturnValue_t PlocSupvHelper::handleTmReception(size_t remainingBytes, uint32_t return result; } +ReturnValue_t PlocSupvHelper::checkReceivedTm(ploc::SpTmReader& reader) { + ReturnValue_t result = reader.checkSize(); + if (result != RETURN_OK) { + triggerEvent(SUPV_REPLY_SIZE_MISSMATCH, rememberApid); + return result; + } + result = reader.checkCrc(); + if (result != RETURN_OK) { + triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); + return result; + } + return result; +} + ReturnValue_t PlocSupvHelper::receive(uint8_t* data, size_t* readBytes, size_t requestBytes) { ReturnValue_t result = RETURN_OK; uint8_t* buffer = nullptr; @@ -585,7 +597,7 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception() { return result; } ReturnValue_t result = tmReader.checkCrc(); - if (result != RETURN_OK) { + if(result != RETURN_OK) { triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); return result; } diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 4b0348c9..9531c3cb 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -86,7 +86,8 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha //! [EXPORT] : [COMMENT] Update procedure failed when sending packet with number P1 //! P1: Packet number for which the memory write command fails static const Event WRITE_MEMORY_FAILED = MAKE_EVENT(19, severity::LOW); - static const Event SUPV_REPLY_CRC_MISSMATCH = MAKE_EVENT(20, severity::LOW); + static const Event SUPV_REPLY_SIZE_MISSMATCH = MAKE_EVENT(20, severity::LOW); + static const Event SUPV_REPLY_CRC_MISSMATCH = MAKE_EVENT(21, severity::LOW); PlocSupvHelper(object_id_t objectId); virtual ~PlocSupvHelper(); @@ -225,6 +226,8 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha * failure report. */ ReturnValue_t handleTmReception(size_t remainingBytes, uint32_t timeout = 70000); + ReturnValue_t checkReceivedTm(ploc::SpTmReader& reader); + ReturnValue_t selectMemory(); ReturnValue_t prepareUpdate(); ReturnValue_t eraseMemory(); From 232372fd9660306a665f9eff4cb35f5b5b6e6dbe Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 15 Aug 2022 18:53:25 +0200 Subject: [PATCH 07/58] more defensive buffer handling --- .../PlocSupervisorDefinitions.h | 7 ------- linux/devices/ploc/PlocMPSoCHandler.cpp | 4 ++-- linux/devices/ploc/PlocMPSoCHelper.cpp | 3 +++ linux/devices/ploc/PlocSupervisorHandler.cpp | 1 - linux/devices/ploc/PlocSupvHelper.cpp | 16 ++++++++++++---- linux/devices/ploc/PlocSupvHelper.h | 2 ++ 6 files changed, 19 insertions(+), 14 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index d8c0d515..0b3ef03a 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -159,13 +159,6 @@ static const size_t MAX_PACKET_SIZE = 1024; static const uint8_t SPACE_PACKET_HEADER_LENGTH = 6; -// enum class SequenceFlags : uint8_t { -// CONTINUED_PKT = 0b00, -// FIRST_PKT = 0b01, -// LAST_PKT = 0b10, -// STANDALONE_PKT = 0b11 -// }; - enum PoolIds : lp_id_t { NUM_TMS, TEMP_PS, diff --git a/linux/devices/ploc/PlocMPSoCHandler.cpp b/linux/devices/ploc/PlocMPSoCHandler.cpp index 9df54ed2..b3eea536 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.cpp +++ b/linux/devices/ploc/PlocMPSoCHandler.cpp @@ -19,6 +19,8 @@ PlocMPSoCHandler::PlocMPSoCHandler(object_id_t objectId, object_id_t uartComIFid eventQueue = QueueFactory::instance()->createMessageQueue(EventMessage::EVENT_MESSAGE_SIZE * 5); commandActionHelperQueue = QueueFactory::instance()->createMessageQueue(EventMessage::EVENT_MESSAGE_SIZE * 5); + spParams.maxSize = sizeof(commandBuffer); + spParams.buf = commandBuffer; } PlocMPSoCHandler::~PlocMPSoCHandler() {} @@ -207,8 +209,6 @@ ReturnValue_t PlocMPSoCHandler::buildCommandFromCommand(DeviceCommandId_t device const uint8_t* commandData, size_t commandDataLen) { spParams.buf = commandBuffer; - spParams.maxSize = sizeof(commandBuffer); - ReturnValue_t result = RETURN_OK; switch (deviceCommand) { case (mpsoc::TC_MEM_WRITE): { diff --git a/linux/devices/ploc/PlocMPSoCHelper.cpp b/linux/devices/ploc/PlocMPSoCHelper.cpp index 9156138e..e9a65d64 100644 --- a/linux/devices/ploc/PlocMPSoCHelper.cpp +++ b/linux/devices/ploc/PlocMPSoCHelper.cpp @@ -104,6 +104,7 @@ ReturnValue_t PlocMPSoCHelper::startFlashWrite(std::string obcFile, std::string ReturnValue_t PlocMPSoCHelper::resetHelper() { ReturnValue_t result = RETURN_OK; semaphore.release(); + spParams.buf = commandBuffer; terminate = false; result = uartComIF->flushUartRxBuffer(comCookie); return result; @@ -162,6 +163,7 @@ ReturnValue_t PlocMPSoCHelper::performFlashWrite() { ReturnValue_t PlocMPSoCHelper::flashfopen() { ReturnValue_t result = RETURN_OK; + spParams.buf = commandBuffer; (*sequenceCount)++; mpsoc::FlashFopen flashFopen(spParams, *sequenceCount); result = flashFopen.createPacket(flashWrite.mpsocFile, mpsoc::FlashFopen::APPEND); @@ -177,6 +179,7 @@ ReturnValue_t PlocMPSoCHelper::flashfopen() { ReturnValue_t PlocMPSoCHelper::flashfclose() { ReturnValue_t result = RETURN_OK; + spParams.buf = commandBuffer; (*sequenceCount)++; mpsoc::FlashFclose flashFclose(spParams, *sequenceCount); result = flashFclose.createPacket(flashWrite.mpsocFile); diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 2b6c44d3..6cd8b656 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -201,7 +201,6 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d using namespace supv; ReturnValue_t result = RETURN_FAILED; spParams.buf = commandBuffer; - spParams.maxSize = sizeof(commandBuffer); switch (deviceCommand) { case GET_HK_REPORT: { prepareEmptyCmd(APID_GET_HK_REPORT); diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 54e7c8ba..25566b11 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -17,8 +17,8 @@ #include "mission/utility/Timestamp.h" PlocSupvHelper::PlocSupvHelper(object_id_t objectId) : SystemObject(objectId) { - spParams.buf = commandBuffer; spParams.maxSize = sizeof(commandBuffer); + resetSpParams(); } PlocSupvHelper::~PlocSupvHelper() {} @@ -244,6 +244,7 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { } else { seqFlags = ccsds::SequenceFlags::CONTINUATION; } + resetSpParams(); supv::WriteMemory packet(spParams); result = packet.buildPacket(seqFlags, update.sequenceCount++, update.memoryId, update.startAddress + update.bytesWritten, dataLength, tempData); @@ -271,6 +272,7 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { ReturnValue_t PlocSupvHelper::performEventBufferRequest() { using namespace supv; ReturnValue_t result = RETURN_OK; + resetSpParams(); RequestLoggingData packet(spParams); result = packet.buildPacket(RequestLoggingData::Sa::REQUEST_EVENT_BUFFERS); if (result != RETURN_OK) { @@ -297,6 +299,7 @@ ReturnValue_t PlocSupvHelper::performEventBufferRequest() { ReturnValue_t PlocSupvHelper::selectMemory() { ReturnValue_t result = RETURN_OK; + resetSpParams(); supv::MPSoCBootSelect packet(spParams); result = packet.buildPacket(update.memoryId); if (result != RETURN_OK) { @@ -311,6 +314,7 @@ ReturnValue_t PlocSupvHelper::selectMemory() { ReturnValue_t PlocSupvHelper::prepareUpdate() { ReturnValue_t result = RETURN_OK; + resetSpParams(); supv::ApidOnlyPacket packet(spParams, supv::APID_PREPARE_UPDATE); result = packet.buildPacket(); result = handlePacketTransmission(packet, PREPARE_UPDATE_EXECUTION_REPORT); @@ -322,6 +326,7 @@ ReturnValue_t PlocSupvHelper::prepareUpdate() { ReturnValue_t PlocSupvHelper::eraseMemory() { ReturnValue_t result = RETURN_OK; + resetSpParams(); supv::EraseMemory eraseMemory(spParams); result = eraseMemory.buildPacket(update.memoryId, update.startAddress, update.length); if (result != RETURN_OK) { @@ -376,7 +381,7 @@ ReturnValue_t PlocSupvHelper::handleAck() { } supv::AcknowledgmentReport ackReport(tmBuf.data(), tmBuf.size()); result = checkReceivedTm(ackReport); - if(result != RETURN_OK) { + if (result != RETURN_OK) { return result; } result = ackReport.checkApid(); @@ -403,7 +408,7 @@ ReturnValue_t PlocSupvHelper::handleExe(uint32_t timeout) { } supv::ExecutionReport exeReport(tmBuf.data(), tmBuf.size()); result = checkReceivedTm(exeReport); - if(result != RETURN_OK) { + if (result != RETURN_OK) { return result; } result = exeReport.checkApid(); @@ -516,6 +521,7 @@ ReturnValue_t PlocSupvHelper::calcImageCrc() { ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { ReturnValue_t result = RETURN_OK; + resetSpParams(); // Verification of update write procedure supv::CheckMemory packet(spParams); result = packet.buildPacket(update.memoryId, update.startAddress, update.length); @@ -597,7 +603,7 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception() { return result; } ReturnValue_t result = tmReader.checkCrc(); - if(result != RETURN_OK) { + if (result != RETURN_OK) { triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); return result; } @@ -613,3 +619,5 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception() { } return result; } + +void PlocSupvHelper::resetSpParams() { spParams.buf = commandBuffer; } diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 9531c3cb..c17521d9 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -244,6 +244,8 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha */ uint32_t getFileSize(std::string filename); ReturnValue_t handleEventBufferReception(); + + void resetSpParams(); }; #endif /* BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_ */ From e1c06ce1f50eb966e1825a60c046c65115b44286 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 15 Aug 2022 18:58:56 +0200 Subject: [PATCH 08/58] possible bugfix --- .../devicedefinitions/PlocMPSoCDefinitions.h | 8 ++++---- mission/devices/devicedefinitions/SpBase.h | 13 ++++++++----- 2 files changed, 12 insertions(+), 9 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index adcd4271..eb46791f 100644 --- a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h +++ b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h @@ -174,7 +174,7 @@ class TcBase : public ploc::SpTcBase, public MPSoCReturnValuesIF { } } - updateFields(); + updateSpFields(); res = checkSizeAndSerializeHeader(); if (res != result::OK) { return res; @@ -306,7 +306,7 @@ class FlashFopen : public ploc::SpTcBase { *(spParams.buf + nameSize) = NULL_TERMINATOR; std::memcpy(payloadStart + nameSize + sizeof(NULL_TERMINATOR), &accessMode, sizeof(accessMode)); spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR) + sizeof(accessMode)); - updateFields(); + updateSpFields(); return calcCrc(); } @@ -354,7 +354,7 @@ class TcFlashWrite : public ploc::SpTcBase { } std::memcpy(payloadStart + sizeof(writeLen), writeData, writeLen); spParams.setPayloadLen(static_cast(writeLen) + 4); - updateFields(); + updateSpFields(); auto res = checkSizeAndSerializeHeader(); if (res != result::OK) { return res; @@ -379,7 +379,7 @@ class TcFlashDelete : public ploc::SpTcBase { std::memcpy(payloadStart, filename.c_str(), nameSize); *(payloadStart + nameSize) = NULL_TERMINATOR; spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR)); - updateFields(); + updateSpFields(); auto res = checkSizeAndSerializeHeader(); if (res != result::OK) { return res; diff --git a/mission/devices/devicedefinitions/SpBase.h b/mission/devices/devicedefinitions/SpBase.h index c03c7360..c3a683cb 100644 --- a/mission/devices/devicedefinitions/SpBase.h +++ b/mission/devices/devicedefinitions/SpBase.h @@ -26,16 +26,19 @@ struct SpTcParams { class SpTcBase { public: - SpTcBase(SpTcParams params) : spParams(params) { updateFields(); } + SpTcBase(SpTcParams params) : spParams(params) { + payloadStart = spParams.buf + ccsds::HEADER_LEN; + updateSpFields(); + } SpTcBase(SpTcParams params, uint16_t apid, uint16_t seqCount) : spParams(params) { spParams.creator.setApid(apid); spParams.creator.setSeqCount(seqCount); - updateFields(); + payloadStart = spParams.buf + ccsds::HEADER_LEN; + updateSpFields(); } - void updateFields() { - payloadStart = spParams.buf + ccsds::HEADER_LEN; + void updateSpFields() { spParams.creator.setDataLen(spParams.dataFieldLen - 1); spParams.creator.setPacketType(ccsds::PacketType::TC); } @@ -55,7 +58,7 @@ class SpTcBase { } ReturnValue_t serializeHeader() { - updateFields(); + updateSpFields(); size_t serLen = 0; return spParams.creator.serializeBe(spParams.buf, serLen, spParams.maxSize); } From 67ab3f981b6fc8b9f74f75a40f83975e7fa9aa6c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 15 Aug 2022 19:03:08 +0200 Subject: [PATCH 09/58] missing packet checks --- 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 6cd8b656..b0718e81 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -906,7 +906,10 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) { ReturnValue_t result = RETURN_OK; AcknowledgmentReport ack(data, SIZE_ACK_REPORT); - // ack.addWholeData(data, SIZE_ACK_REPORT); + result = ack.checkSize(); + if(result != RETURN_OK) { + return result; + } result = ack.checkCrc(); if (result != RETURN_OK) { @@ -960,9 +963,6 @@ ReturnValue_t PlocSupervisorHandler::handleExecutionReport(const uint8_t* data) ReturnValue_t result = RETURN_OK; ExecutionReport exe(data, SIZE_EXE_REPORT); - if (exe.isNull()) { - return RETURN_FAILED; - } result = exe.checkSize(); if (result != RETURN_OK) { return result; From eb54a384b4f9bd2b19744815bd7de85348b58cd1 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 15 Aug 2022 19:19:23 +0200 Subject: [PATCH 10/58] bump fsfw --- fsfw | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/fsfw b/fsfw index 4d82d0e4..c57e95c6 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 4d82d0e4c15091aceafc8279790517702d5941f4 +Subproject commit c57e95c69851f8bc15a345eaed9c921ac2030f1d From 17279a6fd0809b0e2ec3609f5e625731c6ba2fd1 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 16 Aug 2022 17:09:46 +0200 Subject: [PATCH 11/58] host compiles --- bsp_hosted/ObjectFactory.cpp | 7 +++---- fsfw | 2 +- mission/core/GenericFactory.cpp | 1 + tmtc | 2 +- unittest/testEnvironment.cpp | 4 ++-- 5 files changed, 8 insertions(+), 8 deletions(-) diff --git a/bsp_hosted/ObjectFactory.cpp b/bsp_hosted/ObjectFactory.cpp index 8129790c..64092bad 100644 --- a/bsp_hosted/ObjectFactory.cpp +++ b/bsp_hosted/ObjectFactory.cpp @@ -45,8 +45,8 @@ #include void Factory::setStaticFrameworkObjectIds() { - PusServiceBase::packetSource = objects::PUS_PACKET_DISTRIBUTOR; - PusServiceBase::packetDestination = objects::TM_FUNNEL; + PusServiceBase::PUS_DISTRIBUTOR = objects::PUS_PACKET_DISTRIBUTOR; + PusServiceBase::PACKET_DESTINATION = objects::TM_FUNNEL; CommandingServiceBase::defaultPacketSource = objects::PUS_PACKET_DISTRIBUTOR; CommandingServiceBase::defaultPacketDestination = objects::TM_FUNNEL; @@ -55,8 +55,7 @@ void Factory::setStaticFrameworkObjectIds() { // No storage object for now. TmFunnel::storageDestination = objects::NO_OBJECT; - VerificationReporter::messageReceiver = objects::PUS_SERVICE_1_VERIFICATION; - TmPacketBase::timeStamperId = objects::TIME_STAMPER; + VerificationReporter::DEFAULT_RECEIVER = objects::PUS_SERVICE_1_VERIFICATION; } void ObjectFactory::produce(void* args) { diff --git a/fsfw b/fsfw index c57e95c6..d815f422 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit c57e95c69851f8bc15a345eaed9c921ac2030f1d +Subproject commit d815f422c394bb87ccf9e9d306cb42bd01f162bc diff --git a/mission/core/GenericFactory.cpp b/mission/core/GenericFactory.cpp index 01fe4e9b..0a9be3f9 100644 --- a/mission/core/GenericFactory.cpp +++ b/mission/core/GenericFactory.cpp @@ -54,6 +54,7 @@ void ObjectFactory::produceGenericObjects(HealthTableIF** healthTable_) { *healthTable_ = healthTable; } new InternalErrorReporter(objects::INTERNAL_ERROR_REPORTER); + new VerificationReporter(); auto* timeStamper = new CdsShortTimeStamper(objects::TIME_STAMPER); { diff --git a/tmtc b/tmtc index 3fa70080..ca9f85de 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 3fa700804e0592db4e9a5667de2a81323cac5dc7 +Subproject commit ca9f85de1b51e29e3c0cccd527d736083e374f7f diff --git a/unittest/testEnvironment.cpp b/unittest/testEnvironment.cpp index e4d5bed2..72726f39 100644 --- a/unittest/testEnvironment.cpp +++ b/unittest/testEnvironment.cpp @@ -7,7 +7,7 @@ #include #include #include -#include +#include #ifdef LINUX ServiceInterfaceStream sif::debug("DEBUG "); @@ -28,7 +28,7 @@ void factory(void* args) { eventManager = new EventManagerMock(); new HealthTable(objects::HEALTH_TABLE); new InternalErrorReporter(objects::INTERNAL_ERROR_REPORTER); - new TimeStamper(objects::TIME_STAMPER); + new CdsShortTimeStamper(objects::TIME_STAMPER); { PoolManager::LocalPoolConfig poolCfg = {{300, 16}, {200, 32}, {150, 64}, {150, 128}, From 595d098653e8185e05445dd0ee99c3f6a96fc631 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 16 Aug 2022 17:43:05 +0200 Subject: [PATCH 12/58] use new API --- mission/controller/AcsController.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 6a453b59..5dd9acd5 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -45,7 +45,8 @@ ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localD localDataPoolMap.emplace(acsctrl::PoolIds::MGM_3_RM3100_UT, &mgm3PoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_IMTQ_CAL_NT, &imtqMgmPoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_IMTQ_CAL_ACT_STATUS, &imtqCalActStatus); - poolManager.subscribeForPeriodicPacket(mgmData.getSid(), false, 5.0, false); + poolManager.subscribeForRegularPeriodicPacket(subdp::RegularHkPeriodicParams( + mgmData.getSid(), false, 5.0)); return HasReturnvaluesIF::RETURN_OK; } From 21903c4443dc2067dca86754ac8f311ddabb49e8 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 16 Aug 2022 17:43:53 +0200 Subject: [PATCH 13/58] that works as well. --- mission/controller/AcsController.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index 5dd9acd5..fb28f45c 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -45,8 +45,7 @@ ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localD localDataPoolMap.emplace(acsctrl::PoolIds::MGM_3_RM3100_UT, &mgm3PoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_IMTQ_CAL_NT, &imtqMgmPoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_IMTQ_CAL_ACT_STATUS, &imtqCalActStatus); - poolManager.subscribeForRegularPeriodicPacket(subdp::RegularHkPeriodicParams( - mgmData.getSid(), false, 5.0)); + poolManager.subscribeForRegularPeriodicPacket({mgmData.getSid(), false, 5.0}); return HasReturnvaluesIF::RETURN_OK; } From 6ead94b5f494f99b8b8a119d01389ada1f86be82 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 16 Aug 2022 17:49:50 +0200 Subject: [PATCH 14/58] this is even better --- bsp_q7s/core/CoreController.cpp | 3 +-- fsfw | 2 +- linux/devices/GPSHyperionLinuxController.cpp | 3 +-- mission/controller/AcsController.cpp | 2 +- 4 files changed, 4 insertions(+), 6 deletions(-) diff --git a/bsp_q7s/core/CoreController.cpp b/bsp_q7s/core/CoreController.cpp index 1f07fbb3..25d47b7c 100644 --- a/bsp_q7s/core/CoreController.cpp +++ b/bsp_q7s/core/CoreController.cpp @@ -92,8 +92,7 @@ ReturnValue_t CoreController::initializeLocalDataPool(localpool::DataPool &local localDataPoolMap.emplace(core::TEMPERATURE, new PoolEntry({0})); localDataPoolMap.emplace(core::PS_VOLTAGE, new PoolEntry({0})); localDataPoolMap.emplace(core::PL_VOLTAGE, new PoolEntry({0})); - poolManager.subscribeForRegularPeriodicPacket( - subdp::RegularHkPeriodicParams(hkSet.getSid(), false, 10.0)); + poolManager.subscribeForRegularPeriodicPacket({hkSet.getSid(), false, 10.0}); return HasReturnvaluesIF::RETURN_OK; } diff --git a/fsfw b/fsfw index cdd0ca70..34c714eb 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit cdd0ca70edc3691e7d46677626e5c75d324ec1b4 +Subproject commit 34c714eb171acd807fbed687038ba5bc48da41c2 diff --git a/linux/devices/GPSHyperionLinuxController.cpp b/linux/devices/GPSHyperionLinuxController.cpp index 81e0b951..32e3e40d 100644 --- a/linux/devices/GPSHyperionLinuxController.cpp +++ b/linux/devices/GPSHyperionLinuxController.cpp @@ -87,8 +87,7 @@ ReturnValue_t GPSHyperionLinuxController::initializeLocalDataPool( localDataPoolMap.emplace(GpsHyperion::SATS_IN_USE, new PoolEntry()); localDataPoolMap.emplace(GpsHyperion::SATS_IN_VIEW, new PoolEntry()); localDataPoolMap.emplace(GpsHyperion::FIX_MODE, new PoolEntry()); - poolManager.subscribeForRegularPeriodicPacket( - subdp::RegularHkPeriodicParams(gpsSet.getSid(), false, 30.0)); + poolManager.subscribeForRegularPeriodicPacket({gpsSet.getSid(), 30.0}); return HasReturnvaluesIF::RETURN_OK; } diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index fb28f45c..c9e237bb 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -45,7 +45,7 @@ ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localD localDataPoolMap.emplace(acsctrl::PoolIds::MGM_3_RM3100_UT, &mgm3PoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_IMTQ_CAL_NT, &imtqMgmPoolVec); localDataPoolMap.emplace(acsctrl::PoolIds::MGM_IMTQ_CAL_ACT_STATUS, &imtqCalActStatus); - poolManager.subscribeForRegularPeriodicPacket({mgmData.getSid(), false, 5.0}); + poolManager.subscribeForRegularPeriodicPacket({mgmData.getSid(), 5.0}); return HasReturnvaluesIF::RETURN_OK; } From 91600bcce9e5fed88bb87524517b55ee8ab4a562 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 16 Aug 2022 17:51:36 +0200 Subject: [PATCH 15/58] remove redundant call --- linux/devices/devicedefinitions/PlocMPSoCDefinitions.h | 1 - 1 file changed, 1 deletion(-) diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index eb46791f..25837e00 100644 --- a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h +++ b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h @@ -225,7 +225,6 @@ class TcMemRead : public TcBase { if (result != HasReturnvaluesIF::RETURN_OK) { return result; } - spParams.setPayloadLen(MEM_ADDRESS_SIZE + MEM_LEN_SIZE); return result; } From 800cabb8a1d744847e86afa3047a9ae26c51b6bb Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 16 Aug 2022 18:02:32 +0200 Subject: [PATCH 16/58] small bugfix --- .../devicedefinitions/PlocMPSoCDefinitions.h | 21 +++++++++++++------ 1 file changed, 15 insertions(+), 6 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index 25837e00..b3b456d8 100644 --- a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h +++ b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h @@ -257,7 +257,7 @@ class TcMemWrite : public TcBase { : TcBase(params, apid::TC_MEM_WRITE, sequenceCount) {} protected: - // TODO: Confusing, recheck.. + ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; result = lengthCheck(commandDataLen); @@ -267,19 +267,28 @@ class TcMemWrite : public TcBase { std::memcpy(payloadStart, commandData, commandDataLen); uint16_t memLen = *(commandData + MEM_ADDRESS_SIZE) << 8 | *(commandData + MEM_ADDRESS_SIZE + 1); - spParams.setPayloadLen(FIX_LENGTH + memLen * 4); + spParams.setPayloadLen(MIN_FIXED_PAYLOAD_LENGTH + memLen * 4); return result; } private: - // Min length consists of 4 byte address, 2 byte mem length field, 4 byte data (1 word) - static const size_t MIN_COMMAND_DATA_LENGTH = 10; + // 4 byte address, 2 byte mem length field static const size_t MEM_ADDRESS_SIZE = 4; - static const size_t FIX_LENGTH = 8; + static const size_t MIN_FIXED_PAYLOAD_LENGTH = MEM_ADDRESS_SIZE + 2; + // Min length consists of 4 byte address, 2 byte mem length field, 4 byte data (1 word) + static const size_t MIN_COMMAND_DATA_LENGTH = MIN_FIXED_PAYLOAD_LENGTH + 4; + + ReturnValue_t lengthCheck(size_t commandDataLen) { if (commandDataLen < MIN_COMMAND_DATA_LENGTH) { - sif::warning << "TcMemWrite: Command has invalid length " << commandDataLen << std::endl; + sif::warning << "TcMemWrite: Length " << commandDataLen << " smaller than minimum " << + MIN_COMMAND_DATA_LENGTH << std::endl; + return INVALID_LENGTH; + } + if(commandDataLen + CRC_SIZE > spParams.maxSize) { + sif::warning << "TcMemWrite: Length " << commandDataLen << " larger than allowed " << + spParams.maxSize - CRC_SIZE << std::endl; return INVALID_LENGTH; } return HasReturnvaluesIF::RETURN_OK; From 5c32114bdb956a8a075c9a5fdb47a7a5d7ea5d4c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 16 Aug 2022 18:13:54 +0200 Subject: [PATCH 17/58] this check is sufficient --- 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 0b3ef03a..37275b10 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -1080,7 +1080,7 @@ class WriteMemory : public ploc::SpTcBase { ReturnValue_t buildPacket(ccsds::SequenceFlags seqFlags, uint16_t sequenceCount, uint8_t memoryId, uint32_t startAddress, uint16_t length, uint8_t* updateData) { - if (length > CHUNK_MAX + 1) { + if (length > CHUNK_MAX) { sif::error << "WriteMemory::WriteMemory: Invalid length" << std::endl; return SerializeIF::BUFFER_TOO_SHORT; } From e649d45e3e65226a380c51218799bb50129b852a Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 16 Aug 2022 18:37:51 +0200 Subject: [PATCH 18/58] better size checks --- .../devicedefinitions/PlocMPSoCDefinitions.h | 62 ++++++++++++++----- .../PlocSupervisorDefinitions.h | 10 ++- 2 files changed, 54 insertions(+), 18 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index b3b456d8..f92cfd22 100644 --- a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h +++ b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h @@ -237,7 +237,7 @@ class TcMemRead : public TcBase { uint16_t memLen = 0; ReturnValue_t lengthCheck(size_t commandDataLen) { - if (commandDataLen != COMMAND_LENGTH) { + if (commandDataLen != COMMAND_LENGTH or checkPayloadLen() != HasReturnvaluesIF::RETURN_OK) { return INVALID_LENGTH; } return HasReturnvaluesIF::RETURN_OK; @@ -264,10 +264,14 @@ class TcMemWrite : public TcBase { if (result != HasReturnvaluesIF::RETURN_OK) { return result; } - std::memcpy(payloadStart, commandData, commandDataLen); uint16_t memLen = *(commandData + MEM_ADDRESS_SIZE) << 8 | *(commandData + MEM_ADDRESS_SIZE + 1); spParams.setPayloadLen(MIN_FIXED_PAYLOAD_LENGTH + memLen * 4); + result = checkPayloadLen(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + std::memcpy(payloadStart, commandData, commandDataLen); return result; } @@ -279,7 +283,6 @@ class TcMemWrite : public TcBase { static const size_t MIN_COMMAND_DATA_LENGTH = MIN_FIXED_PAYLOAD_LENGTH + 4; - ReturnValue_t lengthCheck(size_t commandDataLen) { if (commandDataLen < MIN_COMMAND_DATA_LENGTH) { sif::warning << "TcMemWrite: Length " << commandDataLen << " smaller than minimum " << @@ -310,10 +313,14 @@ 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)); + ReturnValue_t result = checkPayloadLen(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } std::memcpy(payloadStart, filename.c_str(), nameSize); *(spParams.buf + nameSize) = NULL_TERMINATOR; std::memcpy(payloadStart + nameSize + sizeof(NULL_TERMINATOR), &accessMode, sizeof(accessMode)); - spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR) + sizeof(accessMode)); updateSpFields(); return calcCrc(); } @@ -325,16 +332,20 @@ class FlashFopen : public ploc::SpTcBase { /** * @brief Class to help creation of flash fclose command. */ -class FlashFclose : public TcBase { +class FlashFclose : public ploc::SpTcBase { public: FlashFclose(ploc::SpTcParams params, uint16_t sequenceCount) - : TcBase(params, apid::TC_FLASHFCLOSE, sequenceCount) {} + : ploc::SpTcBase(params, apid::TC_FLASHFCLOSE, sequenceCount) {} ReturnValue_t createPacket(std::string filename) { size_t nameSize = filename.size(); + spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR)); + ReturnValue_t result = checkPayloadLen(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } std::memcpy(payloadStart, filename.c_str(), nameSize); *(payloadStart + nameSize) = NULL_TERMINATOR; - spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR)); return calcCrc(); } }; @@ -354,6 +365,11 @@ class TcFlashWrite : public ploc::SpTcBase { sif::debug << "FlashWrite::createPacket: Command data too big" << std::endl; return HasReturnvaluesIF::RETURN_FAILED; } + spParams.setPayloadLen(static_cast(writeLen) + 4); + result = checkPayloadLen(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } size_t serializedSize = 0; result = SerializeAdapter::serialize(&writeLen, payloadStart, &serializedSize, sizeof(writeLen), SerializeIF::Endianness::BIG); @@ -361,7 +377,6 @@ class TcFlashWrite : public ploc::SpTcBase { return result; } std::memcpy(payloadStart + sizeof(writeLen), writeData, writeLen); - spParams.setPayloadLen(static_cast(writeLen) + 4); updateSpFields(); auto res = checkSizeAndSerializeHeader(); if (res != result::OK) { @@ -384,11 +399,16 @@ class TcFlashDelete : public ploc::SpTcBase { ReturnValue_t buildPacket(std::string filename) { size_t nameSize = filename.size(); + spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR)); + auto res = checkPayloadLen(); + if(res != HasReturnvaluesIF::RETURN_OK) { + return res; + } std::memcpy(payloadStart, filename.c_str(), nameSize); *(payloadStart + nameSize) = NULL_TERMINATOR; - spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR)); + updateSpFields(); - auto res = checkSizeAndSerializeHeader(); + res = checkSizeAndSerializeHeader(); if (res != result::OK) { return res; } @@ -419,6 +439,7 @@ class TcReplayStart : public TcBase { protected: ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + spParams.setPayloadLen(commandDataLen); result = lengthCheck(commandDataLen); if (result != HasReturnvaluesIF::RETURN_OK) { return result; @@ -428,7 +449,6 @@ class TcReplayStart : public TcBase { return result; } std::memcpy(payloadStart, commandData, commandDataLen); - spParams.setPayloadLen(commandDataLen); return result; } @@ -438,7 +458,7 @@ class TcReplayStart : public TcBase { static const uint8_t ONCE = 1; ReturnValue_t lengthCheck(size_t commandDataLen) { - if (commandDataLen != COMMAND_DATA_LENGTH) { + if (commandDataLen != COMMAND_DATA_LENGTH or checkPayloadLen() != HasReturnvaluesIF::RETURN_OK) { sif::warning << "TcReplayStart: Command has invalid length " << commandDataLen << std::endl; return INVALID_LENGTH; } @@ -480,9 +500,13 @@ class TcDownlinkPwrOn : public TcBase { if (result != HasReturnvaluesIF::RETURN_OK) { return result; } + spParams.setPayloadLen(commandDataLen + sizeof(MAX_AMPLITUDE)); + result = checkPayloadLen(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } std::memcpy(payloadStart, commandData, commandDataLen); std::memcpy(payloadStart + commandDataLen, &MAX_AMPLITUDE, sizeof(MAX_AMPLITUDE)); - spParams.setPayloadLen(commandDataLen + sizeof(MAX_AMPLITUDE)); return result; } @@ -547,13 +571,13 @@ class TcReplayWriteSeq : public TcBase { protected: ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; + spParams.setPayloadLen(commandDataLen + sizeof(NULL_TERMINATOR)); result = lengthCheck(commandDataLen); if (result != HasReturnvaluesIF::RETURN_OK) { return result; } std::memcpy(payloadStart, commandData, commandDataLen); *(payloadStart + commandDataLen) = NULL_TERMINATOR; - spParams.setPayloadLen(commandDataLen + sizeof(NULL_TERMINATOR)); return result; } @@ -561,7 +585,8 @@ class TcReplayWriteSeq : public TcBase { static const size_t USE_DECODING_LENGTH = 1; ReturnValue_t lengthCheck(size_t commandDataLen) { - if (commandDataLen > USE_DECODING_LENGTH + MAX_FILENAME_SIZE) { + if (commandDataLen > USE_DECODING_LENGTH + MAX_FILENAME_SIZE or + checkPayloadLen() != HasReturnvaluesIF::RETURN_OK) { sif::warning << "TcReplayWriteSeq: Command has invalid length " << commandDataLen << std::endl; return INVALID_LENGTH; @@ -632,12 +657,17 @@ class TcCamcmdSend : public TcBase { return INVALID_LENGTH; } uint16_t dataLen = static_cast(commandDataLen + sizeof(CARRIAGE_RETURN)); + spParams.setPayloadLen(sizeof(dataLen) + commandDataLen + sizeof(CARRIAGE_RETURN)); + auto res = checkPayloadLen(); + if(res != HasReturnvaluesIF::RETURN_OK) { + return res; + } size_t size = sizeof(dataLen); SerializeAdapter::serialize(&dataLen, payloadStart, &size, sizeof(dataLen), SerializeIF::Endianness::BIG); std::memcpy(payloadStart + sizeof(dataLen), commandData, commandDataLen); *(payloadStart + sizeof(dataLen) + commandDataLen) = CARRIAGE_RETURN; - spParams.setPayloadLen(sizeof(dataLen) + commandDataLen + sizeof(CARRIAGE_RETURN)); + return HasReturnvaluesIF::RETURN_OK; } diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 37275b10..8ed6778a 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -1101,7 +1101,7 @@ class WriteMemory : public ploc::SpTcBase { static const uint16_t META_DATA_LENGTH = 8; uint8_t n = 1; - void initPacket(uint8_t memoryId, uint32_t startAddr, uint16_t updateDataLen, + ReturnValue_t initPacket(uint8_t memoryId, uint32_t startAddr, uint16_t updateDataLen, uint8_t* updateData) { size_t serializedSize = 0; uint8_t* data = payloadStart; @@ -1113,7 +1113,6 @@ class WriteMemory : public ploc::SpTcBase { SerializeIF::Endianness::BIG); SerializeAdapter::serialize(&updateDataLen, &data, &serializedSize, sizeof(updateDataLen), SerializeIF::Endianness::BIG); - std::memcpy(data, updateData, updateDataLen); if (updateDataLen % 2 != 0) { spParams.setPayloadLen(META_DATA_LENGTH + updateDataLen + 1); // The data field must be two bytes aligned. Thus, in case the number of bytes to write is odd @@ -1122,6 +1121,13 @@ class WriteMemory : public ploc::SpTcBase { } else { spParams.setPayloadLen(META_DATA_LENGTH + updateDataLen); } + // To avoid crashes in this unexpected case + ReturnValue_t result = checkPayloadLen(); + if(result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + std::memcpy(data, updateData, updateDataLen); + return HasReturnvaluesIF::RETURN_OK; } }; From 0c9018c0c93bc31e273a22422e94412bd7f0a69c Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 16 Aug 2022 18:41:50 +0200 Subject: [PATCH 19/58] specify where some info is coming from --- linux/devices/devicedefinitions/PlocMPSoCDefinitions.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index f92cfd22..aa0f85b8 100644 --- a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h +++ b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h @@ -91,7 +91,9 @@ static const uint16_t LENGTH_TC_MEM_WRITE = 12; static const uint16_t LENGTH_TC_MEM_READ = 8; /** - * TODO: Might be a good idea to document where this is coming from + * Maximum SP packet size as specified in the TAS Supversior ICD. + * https://eive-cloud.irs.uni-stuttgart.de/index.php/apps/files/?dir=/EIVE_TAS-ILH-IRS/ICD-PLOC/TAS&fileid=942896 + * at sheet README */ static constexpr size_t SP_MAX_SIZE = 1024; static const size_t MAX_REPLY_SIZE = SP_MAX_SIZE * 3; From 2d795c6dd024ba80535ccc4b22b4565c4d6a2ff3 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 17 Aug 2022 09:27:19 +0200 Subject: [PATCH 20/58] add sun sensor set --- mission/controller/AcsController.h | 19 ++++++++++- .../AcsCtrlDefinitions.h | 33 +++++++++++++++++-- 2 files changed, 49 insertions(+), 3 deletions(-) diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index 246506b9..4fa00283 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -8,6 +8,7 @@ #include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" #include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" #include "mission/devices/devicedefinitions/IMTQHandlerDefinitions.h" +#include "mission/devices/devicedefinitions/SusDefinitions.h" class AcsController : public ExtendedControllerBase { public: @@ -54,9 +55,25 @@ class AcsController : public ExtendedControllerBase { void copyMgmData(); + + // Sun Sensors + std::array susSets { + SUS::SusDataset(objects::SUS_0_N_LOC_XFYFZM_PT_XF), + SUS::SusDataset(objects::SUS_1_N_LOC_XBYFZM_PT_XB), + SUS::SusDataset(objects::SUS_2_N_LOC_XFYBZB_PT_YB), + SUS::SusDataset(objects::SUS_3_N_LOC_XFYBZF_PT_YF), + SUS::SusDataset(objects::SUS_4_N_LOC_XMYFZF_PT_ZF), + SUS::SusDataset(objects::SUS_5_N_LOC_XFYMZB_PT_ZB), + SUS::SusDataset(objects::SUS_6_R_LOC_XFYBZM_PT_XF), + SUS::SusDataset(objects::SUS_7_R_LOC_XBYBZM_PT_XB), + SUS::SusDataset(objects::SUS_8_R_LOC_XBYBZB_PT_YB), + SUS::SusDataset(objects::SUS_9_R_LOC_XBYBZB_PT_YF), + SUS::SusDataset(objects::SUS_10_N_LOC_XMYBZF_PT_ZF), + SUS::SusDataset(objects::SUS_11_R_LOC_XBYMZB_PT_ZB), + }; + // Initial delay to make sure all pool variables have been initialized their owners Countdown initialCountdown = Countdown(INIT_DELAY); - // Sun Sensors }; #endif /* MISSION_CONTROLLER_ACSCONTROLLER_H_ */ diff --git a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h index cec18a63..c3a97f0d 100644 --- a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h +++ b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h @@ -8,7 +8,10 @@ namespace acsctrl { -enum SetIds : uint32_t { MGM_SENSOR_DATA }; +enum SetIds : uint32_t { + MGM_SENSOR_DATA, + SUS_SENSOR_DATA +}; enum PoolIds : lp_id_t { MGM_0_LIS3_UT, @@ -16,10 +19,29 @@ enum PoolIds : lp_id_t { MGM_2_LIS3_UT, MGM_3_RM3100_UT, MGM_IMTQ_CAL_NT, - MGM_IMTQ_CAL_ACT_STATUS + MGM_IMTQ_CAL_ACT_STATUS, + + SUS_0_N_LOC_XFYFZM_PT_XF, + SUS_6_R_LOC_XFYBZM_PT_XF, + + SUS_1_N_LOC_XBYFZM_PT_XB, + SUS_7_R_LOC_XBYBZM_PT_XB, + + SUS_2_N_LOC_XFYBZB_PT_YB, + SUS_8_R_LOC_XBYBZB_PT_YB, + + SUS_3_N_LOC_XFYBZF_PT_YF, + SUS_9_R_LOC_XBYBZB_PT_YF, + + SUS_4_N_LOC_XMYFZF_PT_ZF, + SUS_10_N_LOC_XMYBZF_PT_ZF, + + SUS_5_N_LOC_XFYMZB_PT_ZB, + SUS_11_R_LOC_XBYMZB_PT_ZB, }; static constexpr uint8_t MGM_SET_ENTRIES = 10; +static constexpr uint8_t SUS_SET_ENTRIES = 12; /** * @brief This dataset can be used to store the collected temperatures of all temperature sensors @@ -41,6 +63,13 @@ class MgmData : public StaticLocalDataSet { private: }; + +class SusData: public StaticLocalDataSet { +public: + SusData(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, SUS_SENSOR_DATA) {} +private: +}; + } // namespace acsctrl #endif /* MISSION_CONTROLLER_CONTROLLERDEFINITIONS_ACSCTRLDEFINITIONS_H_ */ From d9321a83cff0e8e3c10c07e193d2ba99b9ddc5c1 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 18 Aug 2022 11:25:39 +0200 Subject: [PATCH 21/58] retval translation still fails --- fsfw | 2 +- generators/bsp_q7s_events.csv | 4 + generators/bsp_q7s_objects.csv | 3 +- generators/bsp_q7s_returnvalues.csv | 793 +++++++++--------- generators/events/translateEvents.cpp | 16 +- generators/objects/translateObjects.cpp | 13 +- linux/fsfwconfig/events/translateEvents.cpp | 16 +- linux/fsfwconfig/objects/translateObjects.cpp | 13 +- tmtc | 2 +- 9 files changed, 451 insertions(+), 411 deletions(-) diff --git a/fsfw b/fsfw index 34c714eb..7881f5ba 160000 --- a/fsfw +++ b/fsfw @@ -1 +1 @@ -Subproject commit 34c714eb171acd807fbed687038ba5bc48da41c2 +Subproject commit 7881f5bab86212035b94f4995551d75e843174b5 diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index c08a6675..d4258cb6 100644 --- a/generators/bsp_q7s_events.csv +++ b/generators/bsp_q7s_events.csv @@ -159,6 +159,8 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 12609;0x3141;MPSOC_ACK_INVALID_APID;LOW;Expected acknowledgment report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/devices/ploc/PlocMPSoCHelper.h 12610;0x3142;MPSOC_EXE_INVALID_APID;LOW;Expected execution report but received space packet with other apid P1: Apid of received space packet P2: Internal state of MPSoC;linux/devices/ploc/PlocMPSoCHelper.h 12611;0x3143;MPSOC_HELPER_SEQ_CNT_MISMATCH;LOW;Received sequence count does not match expected sequence count P1: Expected sequence count P2: Received sequence count;linux/devices/ploc/PlocMPSoCHelper.h +12612;0x3144;MPSOC_TM_SIZE_ERROR;LOW;;linux/devices/ploc/PlocMPSoCHelper.h +12613;0x3145;MPSOC_TM_CRC_MISSMATCH;LOW;;linux/devices/ploc/PlocMPSoCHelper.h 12700;0x319c;TRANSITION_BACK_TO_OFF;MEDIUM;Could not transition properly and went back to ALL OFF;mission/devices/PayloadPcduHandler.h 12701;0x319d;NEG_V_OUT_OF_BOUNDS;MEDIUM;P1: 0 -> too low, 1 -> too high P2: Float value;mission/devices/PayloadPcduHandler.h 12702;0x319e;U_DRO_OUT_OF_BOUNDS;MEDIUM;P1: 0 -> too low, 1 -> too high P2: Float value;mission/devices/PayloadPcduHandler.h @@ -204,6 +206,8 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 13617;0x3531;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 13618;0x3532;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 13619;0x3533;WRITE_MEMORY_FAILED;LOW;Update procedure failed when sending packet with number P1 P1: Packet number for which the memory write command fails;linux/devices/ploc/PlocSupvHelper.h +13620;0x3534;SUPV_REPLY_SIZE_MISSMATCH;LOW;;linux/devices/ploc/PlocSupvHelper.h +13621;0x3535;SUPV_REPLY_CRC_MISSMATCH;LOW;;linux/devices/ploc/PlocSupvHelper.h 13700;0x3584;ALLOC_FAILURE;MEDIUM;;bsp_q7s/core/CoreController.h 13701;0x3585;REBOOT_SW;MEDIUM; Software reboot occurred. Can also be a systemd reboot. P1: Current Chip, P2: Current Copy;bsp_q7s/core/CoreController.h 13702;0x3586;REBOOT_MECHANISM_TRIGGERED;MEDIUM;The reboot mechanism was triggered. P1: First 16 bits: Last Chip, Last 16 bits: Last Copy, P2: Each byte is the respective reboot count for the slots;bsp_q7s/core/CoreController.h diff --git a/generators/bsp_q7s_objects.csv b/generators/bsp_q7s_objects.csv index 09a96584..53ddb3a6 100644 --- a/generators/bsp_q7s_objects.csv +++ b/generators/bsp_q7s_objects.csv @@ -1,6 +1,6 @@ 0x00005060;P60DOCK_TEST_TASK +0x43000002;ACS_CONTROLLER 0x43000003;CORE_CONTROLLER -0x43100002;ACS_CONTROLLER 0x43400001;THERMAL_CONTROLLER 0x44120006;MGM_0_LIS3_HANDLER 0x44120010;GYRO_0_ADIS_HANDLER @@ -106,6 +106,7 @@ 0x534f0200;TM_STORE 0x534f0300;IPC_STORE 0x53500010;TIME_STAMPER +0x53500020;VERIFICATION_REPORTER 0x53ffffff;FSFW_OBJECTS_END 0x54000010;SPI_TEST 0x54000020;UART_TEST diff --git a/generators/bsp_q7s_returnvalues.csv b/generators/bsp_q7s_returnvalues.csv index b614f324..ab196298 100644 --- a/generators/bsp_q7s_returnvalues.csv +++ b/generators/bsp_q7s_returnvalues.csv @@ -1,169 +1,169 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x0000;OK;System-wide code for ok.;0;HasReturnvaluesIF;fsfw/returnvalues/HasReturnvaluesIF.h 0x0001;Failed;Unspecified system-wide code for failed.;1;HasReturnvaluesIF;fsfw/returnvalues/HasReturnvaluesIF.h -0x5fa0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CCSDSHandler.h -0x5c00;GOMS_PacketTooLong;;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5c01;GOMS_InvalidTableId;;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5c02;GOMS_InvalidAddress;;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5c03;GOMS_InvalidParamSize;;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5c04;GOMS_InvalidPayloadSize;;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x5c05;GOMS_UnknownReplyId;;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h -0x51b0;RWHA_SpiWriteFailure;;176;RW_HANDLER;mission/devices/RwHandler.h -0x51b1;RWHA_SpiReadFailure;Used by the spi send function to tell a failing read call;177;RW_HANDLER;mission/devices/RwHandler.h -0x51b2;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 -0x51b3;RWHA_InvalidSubstitute;Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination;179;RW_HANDLER;mission/devices/RwHandler.h -0x51b4;RWHA_MissingEndSign;HDLC decoding mechanism never receives the end sign 0x7E;180;RW_HANDLER;mission/devices/RwHandler.h -0x51b5;RWHA_NoReply;Reaction wheel only responds with empty frames.;181;RW_HANDLER;mission/devices/RwHandler.h -0x51b6;RWHA_NoStartMarker;Expected a start marker as first byte;182;RW_HANDLER;mission/devices/RwHandler.h -0x51a0;RWHA_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;RW_HANDLER;mission/devices/RwHandler.h -0x51a1;RWHA_InvalidRampTime;Action Message with invalid ramp time was received.;161;RW_HANDLER;mission/devices/RwHandler.h -0x51a2;RWHA_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;RW_HANDLER;mission/devices/RwHandler.h -0x51a3;RWHA_ExecutionFailed;Command execution failed;163;RW_HANDLER;mission/devices/RwHandler.h -0x51a4;RWHA_CrcError;Reaction wheel reply has invalid crc;164;RW_HANDLER;mission/devices/RwHandler.h -0x4ea1;HEATER_CommandNotSupported;;161;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4ea2;HEATER_InitFailed;;162;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4ea3;HEATER_InvalidSwitchNr;;163;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4ea4;HEATER_MainSwitchSetTimeout;;164;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x4ea5;HEATER_CommandAlreadyWaiting;;165;HEATER_HANDLER;mission/devices/HeaterHandler.h -0x57a0;SUSS_ErrorUnlockMutex;;160;SUS_HANDLER;mission/devices/SusHandler.h -0x57a1;SUSS_ErrorLockMutex;;161;SUS_HANDLER;mission/devices/SusHandler.h -0x50a0;IMTQ_InvalidCommandCode;;160;IMTQ_HANDLER;mission/devices/IMTQHandler.h -0x50a1;IMTQ_ParameterMissing;;161;IMTQ_HANDLER;mission/devices/IMTQHandler.h -0x50a2;IMTQ_ParameterInvalid;;162;IMTQ_HANDLER;mission/devices/IMTQHandler.h -0x50a3;IMTQ_CcUnavailable;;163;IMTQ_HANDLER;mission/devices/IMTQHandler.h -0x50a4;IMTQ_InternalProcessingError;;164;IMTQ_HANDLER;mission/devices/IMTQHandler.h -0x50a5;IMTQ_RejectedWithoutReason;;165;IMTQ_HANDLER;mission/devices/IMTQHandler.h -0x50a6;IMTQ_CmdErrUnknown;;166;IMTQ_HANDLER;mission/devices/IMTQHandler.h -0x50a7;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 -0x4fa0;SYRLINKS_CrcFailure;;160;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h -0x4fa1;SYRLINKS_UartFraminOrParityErrorAck;;161;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h -0x4fa2;SYRLINKS_BadCharacterAck;;162;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h -0x4fa3;SYRLINKS_BadParameterValueAck;;163;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h -0x4fa4;SYRLINKS_BadEndOfFrameAck;;164;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h -0x4fa5;SYRLINKS_UnknownCommandIdAck;;165;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h -0x4fa6;SYRLINKS_BadCrcAck;;166;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h -0x4fa7;SYRLINKS_ReplyWrongSize;;167;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h -0x4fa8;SYRLINKS_MissingStartFrameCharacter;;168;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h -0x65a0;SADPL_CommandNotSupported;;160;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h -0x65a1;SADPL_DeploymentAlreadyExecuting;;161;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h -0x65a2;SADPL_MainSwitchTimeoutFailure;;162;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h -0x65a3;SADPL_SwitchingDeplSa1Failed;;163;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h -0x65a4;SADPL_SwitchingDeplSa2Failed;;164;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h -0x62a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NVMParameterBase.h -0x2b01;CCS_BcIsSetVrCommand;;1;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2b02;CCS_BcIsUnlockCommand;;2;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bb0;CCS_BcIllegalCommand;;176;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bb1;CCS_BoardReadingNotFinished;;177;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bf0;CCS_NsPositiveW;;240;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bf1;CCS_NsNegativeW;;241;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bf2;CCS_NsLockout;;242;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bf3;CCS_FarmInLockout;;243;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bf4;CCS_FarmInWait;;244;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2be0;CCS_WrongSymbol;;224;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2be1;CCS_DoubleStart;;225;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2be2;CCS_StartSymbolMissed;;226;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2be3;CCS_EndWithoutStart;;227;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2be4;CCS_TooLarge;;228;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2be5;CCS_TooShort;;229;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2be6;CCS_WrongTfVersion;;230;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2be7;CCS_WrongSpacecraftId;;231;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2be8;CCS_NoValidFrameType;;232;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2be9;CCS_CrcFailed;;233;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bea;CCS_VcNotFound;;234;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2beb;CCS_ForwardingFailed;;235;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bec;CCS_ContentTooLarge;;236;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bed;CCS_ResidualData;;237;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bee;CCS_DataCorrupted;;238;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bef;CCS_IllegalSegmentationFlag;;239;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bd0;CCS_IllegalFlagCombination;;208;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bd1;CCS_ShorterThanHeader;;209;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bd2;CCS_TooShortBlockedPacket;;210;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x2bd3;CCS_TooShortMapExtraction;;211;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h -0x3a00;SPH_ConnBroken;;0;SEMAPHORE_IF;fsfw/src/fsfw/osal/common/TcpTmTcServer.h -0x2901;IEC_NoConfigurationTable;;1;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2902;IEC_NoCpuTable;;2;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2903;IEC_InvalidWorkspaceAddress;;3;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2904;IEC_TooLittleWorkspace;;4;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2905;IEC_WorkspaceAllocation;;5;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2906;IEC_InterruptStackTooSmall;;6;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2907;IEC_ThreadExitted;;7;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2908;IEC_InconsistentMpInformation;;8;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2909;IEC_InvalidNode;;9;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x290a;IEC_NoMpci;;10;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x290b;IEC_BadPacket;;11;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x290c;IEC_OutOfPackets;;12;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x290d;IEC_OutOfGlobalObjects;;13;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x290e;IEC_OutOfProxies;;14;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x290f;IEC_InvalidGlobalId;;15;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2910;IEC_BadStackHook;;16;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2911;IEC_BadAttributes;;17;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2912;IEC_ImplementationKeyCreateInconsistency;;18;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2913;IEC_ImplementationBlockingOperationCancel;;19;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2914;IEC_MutexObtainFromBadState;;20;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h -0x2915;IEC_UnlimitedAndMaximumIs0;;21;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.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 +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 +0x52b3;RWHA_InvalidSubstitute;Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination;179;RW_HANDLER;mission/devices/RwHandler.h +0x52b4;RWHA_MissingEndSign;HDLC decoding mechanism never receives the end sign 0x7E;180;RW_HANDLER;mission/devices/RwHandler.h +0x52b5;RWHA_NoReply;Reaction wheel only responds with empty frames.;181;RW_HANDLER;mission/devices/RwHandler.h +0x52b6;RWHA_NoStartMarker;Expected a start marker as first byte;182;RW_HANDLER;mission/devices/RwHandler.h +0x52a0;RWHA_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;RW_HANDLER;mission/devices/RwHandler.h +0x52a1;RWHA_InvalidRampTime;Action Message with invalid ramp time was received.;161;RW_HANDLER;mission/devices/RwHandler.h +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 +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 +0x50a3;SYRLINKS_BadParameterValueAck;;163;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h +0x50a4;SYRLINKS_BadEndOfFrameAck;;164;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h +0x50a5;SYRLINKS_UnknownCommandIdAck;;165;SYRLINKS_HANDLER;mission/devices/SyrlinksHkHandler.h +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/CCSDSHandler.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/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 +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 +0x4300;FILS_GenericFileError;;0;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4301;FILS_IsBusy;;1;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4302;FILS_InvalidParameters;;2;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4305;FILS_FileDoesNotExist;;5;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4306;FILS_FileAlreadyExists;;6;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4307;FILS_FileLocked;;7;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x430a;FILS_DirectoryDoesNotExist;;10;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x430b;FILS_DirectoryAlreadyExists;;11;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x430c;FILS_DirectoryNotEmpty;;12;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x430f;FILS_SequencePacketMissingWrite;;15;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4310;FILS_SequencePacketMissingRead;;16;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.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 +0x1101;AL_Full;;1;ARRAY_LIST;fsfw/src/fsfw/container/ArrayList.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 +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 -0x2d01;HPA_InvalidIdentifierId;;1;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x2d02;HPA_InvalidDomainId;;2;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x2d03;HPA_InvalidValue;;3;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x2d05;HPA_ReadOnly;;5;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h -0x2c01;PAW_UnknownDatatype;;1;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2c02;PAW_DatatypeMissmatch;;2;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2c03;PAW_Readonly;;3;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2c04;PAW_TooBig;;4;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2c05;PAW_SourceNotSet;;5;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2c06;PAW_OutOfBounds;;6;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2c07;PAW_NotSet;;7;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x2c08;PAW_ColumnOrRowsZero;;8;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h -0x3101;CF_ObjectHasNoFunctions;;1;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h -0x3102;CF_AlreadyCommanding;;2;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h -0x3201;HF_IsBusy;;1;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x3202;HF_InvalidParameters;;2;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x3203;HF_ExecutionFinished;;3;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h -0x3204;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 -0x2500;FDI_YourFault;;0;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h -0x2501;FDI_MyFault;;1;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h -0x2502;FDI_ConfirmLater;;2;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h -0x2101;TMF_Busy;;1;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2102;TMF_LastPacketFound;;2;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2103;TMF_StopFetch;;3;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2104;TMF_Timeout;;4;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2105;TMF_TmChannelFull;;5;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2106;TMF_NotStored;;6;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2107;TMF_AllDeleted;;7;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2108;TMF_InvalidData;;8;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2109;TMF_NotReady;;9;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h -0x2001;TMB_Busy;;1;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2002;TMB_Full;;2;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2003;TMB_Empty;;3;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2004;TMB_NullRequested;;4;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2005;TMB_TooLarge;;5;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2006;TMB_NotReady;;6;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2007;TMB_DumpError;;7;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2008;TMB_CrcError;;8;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x2009;TMB_Timeout;;9;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x200a;TMB_IdlePacketFound;;10;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x200b;TMB_TelecommandFound;;11;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x200c;TMB_NoPusATm;;12;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x200d;TMB_TooSmall;;13;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x200e;TMB_BlockNotFound;;14;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x200f;TMB_InvalidRequest;;15;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h -0x1c01;TCD_PacketLost;;1;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h -0x1c02;TCD_DestinationNotFound;;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h -0x1c03;TCD_ServiceIdAlreadyExists;;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h -0x1b00;TCC_IllegalApid;;0;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h -0x1b01;TCC_IncompletePacket;;1;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h -0x1b02;TCC_IncorrectChecksum;;2;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h -0x1b03;TCC_IllegalPacketType;;3;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h -0x1b04;TCC_IllegalPacketSubtype;;4;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h -0x1b05;TCC_IncorrectPrimaryHeader;;5;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.h -0x1b06;TCC_IncorrectSecondaryHeader;;6;TC_PACKET_CHECK;fsfw/src/fsfw/tcdistribution/TcPacketCheckPUS.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 @@ -204,195 +204,171 @@ 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 -0x2701;SM_DataTooLarge;;1;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2702;SM_DataStorageFull;;2;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2703;SM_IllegalStorageId;;3;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2704;SM_DataDoesNotExist;;4;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2705;SM_IllegalAddress;;5;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x2706;SM_PoolTooLarge;;6;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h -0x37a1;SGP4_InvalidEccentricity;;161;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x37a2;SGP4_InvalidMeanMotion;;162;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x37a3;SGP4_InvalidPerturbationElements;;163;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x37a4;SGP4_InvalidSemiLatusRectum;;164;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x37a5;SGP4_InvalidEpochElements;;165;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x37a6;SGP4_SatelliteHasDecayed;;166;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x37b1;SGP4_TleTooOld;;177;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x37b2;SGP4_TleNotInitialized;;178;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h -0x2301;MT_TooDetailedRequest;;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2302;MT_TooGeneralRequest;;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2303;MT_NoMatch;;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2304;MT_Full;;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x2305;MT_NewNodeCreated;;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h -0x3e01;DLEE_StreamTooShort;;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h -0x3e02;DLEE_DecodingError;;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h -0x2e01;ASC_TooLongForTargetType;;1;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h -0x2e02;ASC_InvalidCharacters;;2;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h -0x2e03;ASC_BufferTooSmall;;3;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h -0x0f01;CM_UnknownCommand;;1;COMMAND_MESSAGE;fsfw/src/fsfw/ipc/CommandMessageIF.h -0x3901;MQI_Empty;;1;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x3902;MQI_Full;No space left for more messages;2;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x3903;MQI_NoReplyPartner;Returned if a reply method was called without partner;3;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x3904;MQI_DestinationInvalid;Returned if the target destination is invalid.;4;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h -0x3801;MUX_NotEnoughResources;;1;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3802;MUX_InsufficientMemory;;2;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3803;MUX_NoPrivilege;;3;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3804;MUX_WrongAttributeSetting;;4;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3805;MUX_MutexAlreadyLocked;;5;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3806;MUX_MutexNotFound;;6;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3807;MUX_MutexMaxLocks;;7;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3808;MUX_CurrThreadAlreadyOwnsMutex;;8;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3809;MUX_CurrThreadDoesNotOwnMutex;;9;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x380a;MUX_MutexTimeout;;10;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x380b;MUX_MutexInvalidId;;11;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x380c;MUX_MutexDestroyedWhileWaiting;;12;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h -0x3a01;SPH_SemaphoreTimeout;;1;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h -0x3a02;SPH_SemaphoreNotOwned;;2;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h -0x3a03;SPH_SemaphoreInvalid;;3;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h -0x3501;CFDP_InvalidTlvType;;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3502;CFDP_InvalidDirectiveFields;;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3503;CFDP_InvalidPduDatafieldLen;;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3504;CFDP_InvalidAckDirectiveFields;;4;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3505;CFDP_MetadataCantParseOptions;;5;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3506;CFDP_FinishedCantParseFsResponses;;6;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3508;CFDP_FilestoreRequiresSecondFile;;8;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x3509;CFDP_FilestoreResponseCantParseFsMessage;;9;CFDP;fsfw/src/fsfw/cfdp/definitions.h -0x2801;TC_InvalidTargetState;;1;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h -0x28f1;TC_AboveOperationalLimit;;241;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h -0x28f2;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 -0x3d00;HKM_QueueOrDestinationInvalid;;0;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3d01;HKM_WrongHkPacketType;;1;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3d02;HKM_ReportingStatusUnchanged;;2;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3d03;HKM_PeriodicHelperInvalid;;3;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3d04;HKM_PoolobjectNotFound;;4;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3d05;HKM_DatasetNotFound;;5;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h -0x3b00;LPIF_PoolEntryNotFound;;0;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h -0x3b01;LPIF_PoolEntryTypeConflict;;1;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h -0x3ca0;PVA_InvalidReadWriteMode;;160;POOL_VARIABLE_IF;fsfw/src/fsfw/datapool/PoolVariableIF.h -0x3ca1;PVA_InvalidPoolEntry;;161;POOL_VARIABLE_IF;fsfw/src/fsfw/datapool/PoolVariableIF.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 0x0802;DPS_SetWasAlreadyRead;;2;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h 0x0803;DPS_CommitingWithoutReading;;3;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h 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 -0x3601;TSI_BadTimestamp;;1;TIME_STAMPER_IF;fsfw/src/fsfw/timemanager/TimeStamperIF.h -0x1d01;PUS_ActivityStarted;;1;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d02;PUS_InvalidSubservice;;2;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d03;PUS_IllegalApplicationData;;3;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d04;PUS_SendTmFailed;;4;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x1d05;PUS_Timeout;;5;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h -0x4b00;SPPA_NoPacketFound;;0;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h -0x4b01;SPPA_SplitPacket;;1;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h -0x1f01;CSB_ExecutionComplete;;1;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x1f02;CSB_NoStepMessage;;2;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x1f03;CSB_ObjectBusy;;3;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x1f04;CSB_Busy;;4;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x1f05;CSB_InvalidTc;;5;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x1f06;CSB_InvalidObject;;6;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h -0x1f07;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 -0x2401;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 -0x2f01;POS_InPowerTransition;;1;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h -0x2f02;POS_SwitchStateMismatch;;2;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h +0x1c01;TCD_PacketLost;;1;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h +0x1c02;TCD_DestinationNotFound;;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h +0x1c03;TCD_ServiceIdAlreadyExists;;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h +0x1b00;TCC_InvalidCcsdsVersion;;0;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b01;TCC_InvalidApid;;1;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b02;TCC_InvalidPacketType;;2;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b03;TCC_InvalidSecHeaderField;;3;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b04;TCC_IncorrectPrimaryHeader;;4;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b05;TCC_IncompletePacket;;5;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b06;TCC_InvalidPusVersion;;6;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b07;TCC_IncorrectChecksum;;7;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b08;TCC_IllegalPacketSubtype;;8;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b09;TCC_IncorrectSecondaryHeader;;9;PACKET_CHECK;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 0x0500;PS_SwitchOff;;0;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h 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 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 0x1a04;TRC_BothValuesOol;;4;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h 0x1a05;TRC_DuplexOol;;5;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h -0x3001;LIM_Unchecked;;1;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x3002;LIM_Invalid;;2;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x3003;LIM_Unselected;;3;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x3004;LIM_BelowLowLimit;;4;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x3005;LIM_AboveHighLimit;;5;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x3006;LIM_UnexpectedValue;;6;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x3007;LIM_OutOfRange;;7;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x30a0;LIM_FirstSample;;160;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x30e0;LIM_InvalidSize;;224;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x30e1;LIM_WrongType;;225;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x30e2;LIM_WrongPid;;226;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x30e3;LIM_WrongLimitId;;227;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x30ee;LIM_MonitorNotFound;;238;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h -0x4101;PUS11_InvalidTypeTimeWindow;;1;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h -0x4102;PUS11_TimeshiftingNotPossible;;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h -0x4103;PUS11_InvalidRelativeTime;;3;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h -0x4200;FILS_GenericFileError;;0;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4201;FILS_IsBusy;;1;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4202;FILS_InvalidParameters;;2;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4205;FILS_FileDoesNotExist;;5;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4206;FILS_FileAlreadyExists;;6;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4207;FILS_FileLocked;;7;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x420a;FILS_DirectoryDoesNotExist;;10;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x420b;FILS_DirectoryAlreadyExists;;11;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x420c;FILS_DirectoryNotEmpty;;12;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x420f;FILS_SequencePacketMissingWrite;;15;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4210;FILS_SequencePacketMissingRead;;16;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.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 +0x3101;LIM_Unchecked;;1;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x3102;LIM_Invalid;;2;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x3103;LIM_Unselected;;3;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x3104;LIM_BelowLowLimit;;4;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x3105;LIM_AboveHighLimit;;5;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x3106;LIM_UnexpectedValue;;6;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x3107;LIM_OutOfRange;;7;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x31a0;LIM_FirstSample;;160;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x31e0;LIM_InvalidSize;;224;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +0x31e1;LIM_WrongType;;225;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h +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_InvalidDirectiveFields;;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_FinishedCantParseFsResponses;;6;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 +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_TimeshiftingNotPossible;;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h +0x4203;PUS11_InvalidRelativeTime;;3;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 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 @@ -402,65 +378,94 @@ 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 -0x3301;DC_NoReplyReceived;;1;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3302;DC_ProtocolError;;2;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3303;DC_Nullpointer;;3;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3304;DC_InvalidCookieType;;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3305;DC_NotActive;;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x3306;DC_TooMuchData;;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h -0x26a0;DHI_NoCommandData;;160;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26a1;DHI_CommandNotSupported;;161;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26a2;DHI_CommandAlreadySent;;162;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26a3;DHI_CommandWasNotSent;;163;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26a4;DHI_CantSwitchAddress;;164;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26a5;DHI_WrongModeForCommand;;165;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26a6;DHI_Timeout;;166;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26a7;DHI_Busy;;167;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26a8;DHI_NoReplyExpected;;168;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26a9;DHI_NonOpTemperature;;169;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26aa;DHI_CommandNotImplemented;;170;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26b0;DHI_ChecksumError;;176;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26b1;DHI_LengthMissmatch;;177;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26b2;DHI_InvalidData;;178;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26b3;DHI_ProtocolError;;179;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26c0;DHI_DeviceDidNotExecute;;192;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26c1;DHI_DeviceReportedError;;193;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26c2;DHI_UnknownDeviceReply;;194;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26c3;DHI_DeviceReplyInvalid;;195;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26d0;DHI_InvalidCommandParameter;;208;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h -0x26d1;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 -0x4400;HSPI_HalTimeoutRetval;;0;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h -0x4401;HSPI_HalBusyRetval;;1;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h -0x4402;HSPI_HalErrorRetval;;2;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h -0x4501;HURT_UartReadFailure;;1;HAL_UART;fsfw/src/fsfw_hal/linux/uart/UartComIF.h -0x4502;HURT_UartReadSizeMissmatch;;2;HAL_UART;fsfw/src/fsfw_hal/linux/uart/UartComIF.h -0x4503;HURT_UartRxBufferTooSmall;;3;HAL_UART;fsfw/src/fsfw_hal/linux/uart/UartComIF.h -0x4701;HGIO_UnknownGpioId;;1;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4702;HGIO_DriveGpioFailure;;2;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4703;HGIO_GpioTypeFailure;;3;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4704;HGIO_GpioInvalidInstance;;4;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4705;HGIO_GpioDuplicateDetected;;5;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4706;HGIO_GpioInitFailed;;6;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4707;HGIO_GpioGetValueFailed;;7;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h -0x4300;UXOS_ExecutionFinished;Execution of the current command has finished;0;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4301;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 -0x4302;UXOS_BytesRead;Some bytes have been read from the executing process;2;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4303;UXOS_CommandError;Command execution failed;3;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4304;UXOS_NoCommandLoadedOrPending;;4;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x4306;UXOS_PcloseCallError;;6;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h -0x63a0;FSHLP_SdNotMounted;SD card specified with path string not mounted;160;FILE_SYSTEM_HELPER;bsp_q7s/memory/FilesystemHelper.h -0x63a1;FSHLP_FileNotExists;Specified file does not exist on filesystem;161;FILE_SYSTEM_HELPER;bsp_q7s/memory/FilesystemHelper.h -0x6900;SDMA_OpOngoing;;0;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h -0x6901;SDMA_AlreadyOn;;1;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h -0x6902;SDMA_AlreadyMounted;;2;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h -0x6903;SDMA_AlreadyOff;;3;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h -0x690a;SDMA_StatusFileNexists;;10;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h -0x690b;SDMA_StatusFileFormatInvalid;;11;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h -0x690c;SDMA_MountError;;12;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h -0x690d;SDMA_UnmountError;;13;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h -0x690e;SDMA_SystemCallError;;14;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h -0x690f;SDMA_PopenCallError;;15;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h -0x6a00;SCBU_KeyNotFound;;0;SCRATCH_BUFFER;bsp_q7s/memory/scratchApi.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 +0x27a3;DHI_CommandWasNotSent;;163;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27a4;DHI_CantSwitchAddress;;164;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27a5;DHI_WrongModeForCommand;;165;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27a6;DHI_Timeout;;166;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27a7;DHI_Busy;;167;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27a8;DHI_NoReplyExpected;;168;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27a9;DHI_NonOpTemperature;;169;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27aa;DHI_CommandNotImplemented;;170;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27b0;DHI_ChecksumError;;176;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27b1;DHI_LengthMissmatch;;177;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27b2;DHI_InvalidData;;178;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27b3;DHI_ProtocolError;;179;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27c0;DHI_DeviceDidNotExecute;;192;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27c1;DHI_DeviceReportedError;;193;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +0x27c2;DHI_UnknownDeviceReply;;194;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h +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_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 +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/memory/FilesystemHelper.h +0x64a1;FSHLP_FileNotExists;Specified file does not exist on filesystem;161;FILE_SYSTEM_HELPER;bsp_q7s/memory/FilesystemHelper.h +0x6a00;SDMA_OpOngoing;;0;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x6a01;SDMA_AlreadyOn;;1;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x6a02;SDMA_AlreadyMounted;;2;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x6a03;SDMA_AlreadyOff;;3;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x6a0a;SDMA_StatusFileNexists;;10;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x6a0b;SDMA_StatusFileFormatInvalid;;11;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x6a0c;SDMA_MountError;;12;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x6a0d;SDMA_UnmountError;;13;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x6a0e;SDMA_SystemCallError;;14;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h +0x6a0f;SDMA_PopenCallError;;15;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h diff --git a/generators/events/translateEvents.cpp b/generators/events/translateEvents.cpp index a3b9468d..18826deb 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 209 translations. + * @brief Auto-generated event translation file. Contains 213 translations. * @details - * Generated on: 2022-08-12 12:30:32 + * Generated on: 2022-08-18 11:23:13 */ #include "translateEvents.h" @@ -165,6 +165,8 @@ 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"; @@ -206,6 +208,8 @@ 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 *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; const char *REBOOT_SW_STRING = "REBOOT_SW"; const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED"; @@ -533,6 +537,10 @@ const char *translateEvents(Event event) { 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): @@ -615,6 +623,10 @@ const char *translateEvents(Event event) { return EXE_RECEPTION_FAILURE_STRING; case (13619): return WRITE_MEMORY_FAILED_STRING; + case (13620): + return SUPV_REPLY_SIZE_MISSMATCH_STRING; + case (13621): + return SUPV_REPLY_CRC_MISSMATCH_STRING; case (13700): return ALLOC_FAILURE_STRING; case (13701): diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index 11b2abf2..a052ec02 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -1,14 +1,14 @@ /** * @brief Auto-generated object translation file. * @details - * Contains 132 translations. - * Generated on: 2022-08-12 12:30:32 + * Contains 133 translations. + * Generated on: 2022-08-18 11:23:13 */ #include "translateObjects.h" const char *P60DOCK_TEST_TASK_STRING = "P60DOCK_TEST_TASK"; -const char *CORE_CONTROLLER_STRING = "CORE_CONTROLLER"; const char *ACS_CONTROLLER_STRING = "ACS_CONTROLLER"; +const char *CORE_CONTROLLER_STRING = "CORE_CONTROLLER"; 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"; @@ -114,6 +114,7 @@ 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"; @@ -143,10 +144,10 @@ const char *translateObject(object_id_t object) { switch ((object & 0xFFFFFFFF)) { case 0x00005060: return P60DOCK_TEST_TASK_STRING; + case 0x43000002: + return ACS_CONTROLLER_STRING; case 0x43000003: return CORE_CONTROLLER_STRING; - case 0x43100002: - return ACS_CONTROLLER_STRING; case 0x43400001: return THERMAL_CONTROLLER_STRING; case 0x44120006: @@ -357,6 +358,8 @@ 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 0x54000010: diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index a3b9468d..18826deb 100644 --- a/linux/fsfwconfig/events/translateEvents.cpp +++ b/linux/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 209 translations. + * @brief Auto-generated event translation file. Contains 213 translations. * @details - * Generated on: 2022-08-12 12:30:32 + * Generated on: 2022-08-18 11:23:13 */ #include "translateEvents.h" @@ -165,6 +165,8 @@ 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"; @@ -206,6 +208,8 @@ 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 *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; const char *REBOOT_SW_STRING = "REBOOT_SW"; const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED"; @@ -533,6 +537,10 @@ const char *translateEvents(Event event) { 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): @@ -615,6 +623,10 @@ const char *translateEvents(Event event) { return EXE_RECEPTION_FAILURE_STRING; case (13619): return WRITE_MEMORY_FAILED_STRING; + case (13620): + return SUPV_REPLY_SIZE_MISSMATCH_STRING; + case (13621): + return SUPV_REPLY_CRC_MISSMATCH_STRING; case (13700): return ALLOC_FAILURE_STRING; case (13701): diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index 11b2abf2..a052ec02 100644 --- a/linux/fsfwconfig/objects/translateObjects.cpp +++ b/linux/fsfwconfig/objects/translateObjects.cpp @@ -1,14 +1,14 @@ /** * @brief Auto-generated object translation file. * @details - * Contains 132 translations. - * Generated on: 2022-08-12 12:30:32 + * Contains 133 translations. + * Generated on: 2022-08-18 11:23:13 */ #include "translateObjects.h" const char *P60DOCK_TEST_TASK_STRING = "P60DOCK_TEST_TASK"; -const char *CORE_CONTROLLER_STRING = "CORE_CONTROLLER"; const char *ACS_CONTROLLER_STRING = "ACS_CONTROLLER"; +const char *CORE_CONTROLLER_STRING = "CORE_CONTROLLER"; 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"; @@ -114,6 +114,7 @@ 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"; @@ -143,10 +144,10 @@ const char *translateObject(object_id_t object) { switch ((object & 0xFFFFFFFF)) { case 0x00005060: return P60DOCK_TEST_TASK_STRING; + case 0x43000002: + return ACS_CONTROLLER_STRING; case 0x43000003: return CORE_CONTROLLER_STRING; - case 0x43100002: - return ACS_CONTROLLER_STRING; case 0x43400001: return THERMAL_CONTROLLER_STRING; case 0x44120006: @@ -357,6 +358,8 @@ 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 0x54000010: diff --git a/tmtc b/tmtc index ca9f85de..7e1eeb85 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit ca9f85de1b51e29e3c0cccd527d736083e374f7f +Subproject commit 7e1eeb85fcee45c3d421a8e344d3678ec6334873 From 732602a4cceb73484b80d186b400ebd162075443 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 18 Aug 2022 15:11:32 +0200 Subject: [PATCH 22/58] supv ack failure --- .../PlocSupervisorDefinitions.h | 20 +++--- linux/devices/ploc/PlocSupervisorHandler.cpp | 62 ++++++++++--------- linux/devices/ploc/PlocSupervisorHandler.h | 2 +- tmtc | 2 +- 4 files changed, 42 insertions(+), 44 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 8ed6778a..b576af7e 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -418,31 +418,25 @@ class SetTimeRef : public ploc::SpTcBase { size_t serializedSize = 0; uint8_t* dataFieldPtr = payloadStart; uint16_t milliseconds = static_cast(time->usecond / 1000) | SYNC; - SerializeAdapter::serialize(&milliseconds, &dataFieldPtr, &serializedSize, + SerializeAdapter::serialize(&milliseconds, &dataFieldPtr, &serializedSize, sizeof(milliseconds), SerializeIF::Endianness::BIG); uint8_t second = static_cast(time->second); - serializedSize = 0; - SerializeAdapter::serialize(&second, &dataFieldPtr, &serializedSize, + SerializeAdapter::serialize(&second, &dataFieldPtr, &serializedSize, sizeof(time->second), SerializeIF::Endianness::BIG); uint8_t minute = static_cast(time->minute); - serializedSize = 0; - SerializeAdapter::serialize(&minute, &dataFieldPtr, &serializedSize, + SerializeAdapter::serialize(&minute, &dataFieldPtr, &serializedSize, sizeof(time->minute), SerializeIF::Endianness::BIG); uint8_t hour = static_cast(time->hour); - serializedSize = 0; - SerializeAdapter::serialize(&hour, &dataFieldPtr, &serializedSize, sizeof(time->hour), + SerializeAdapter::serialize(&hour, &dataFieldPtr, &serializedSize, sizeof(time->hour), SerializeIF::Endianness::BIG); uint8_t day = static_cast(time->day); - serializedSize = 0; - SerializeAdapter::serialize(&day, &dataFieldPtr, &serializedSize, sizeof(time->day), + SerializeAdapter::serialize(&day, &dataFieldPtr, &serializedSize, sizeof(time->day), SerializeIF::Endianness::BIG); uint8_t month = static_cast(time->month); - serializedSize = 0; - SerializeAdapter::serialize(&month, &dataFieldPtr, &serializedSize, + SerializeAdapter::serialize(&month, &dataFieldPtr, &serializedSize, sizeof(time->month), SerializeIF::Endianness::BIG); uint8_t year = static_cast(time->year - 1900); - serializedSize = 0; - SerializeAdapter::serialize(&year, &dataFieldPtr, &serializedSize, sizeof(time->year), + SerializeAdapter::serialize(&year, &dataFieldPtr, &serializedSize, sizeof(time->year), SerializeIF::Endianness::BIG); } }; diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index b0718e81..6789f9f5 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -326,7 +326,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d if (result != RETURN_OK) { break; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); break; } case FACTORY_RESET_CLEAR_MIRROR: { @@ -335,7 +335,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d if (result != RETURN_OK) { break; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); break; } case FACTORY_RESET_CLEAR_CIRCULAR: { @@ -344,7 +344,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d if (result != RETURN_OK) { break; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); break; } case START_MPSOC_QUIET: { @@ -368,7 +368,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d if (result != RETURN_OK) { break; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); break; } case DISABLE_AUTO_TM: { @@ -377,7 +377,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d if (result != RETURN_OK) { break; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); break; } case LOGGING_REQUEST_COUNTERS: { @@ -386,7 +386,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d if (result != RETURN_OK) { break; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); break; } case LOGGING_CLEAR_COUNTERS: { @@ -395,7 +395,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d if (result != RETURN_OK) { break; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); break; } case LOGGING_SET_TOPIC: { @@ -405,7 +405,7 @@ ReturnValue_t PlocSupervisorHandler::buildCommandFromCommand(DeviceCommandId_t d if (result != RETURN_OK) { break; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); break; } case RESET_PL: { @@ -1397,7 +1397,7 @@ ReturnValue_t PlocSupervisorHandler::prepareEmptyCmd(uint16_t apid) { if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1408,7 +1408,7 @@ ReturnValue_t PlocSupervisorHandler::prepareSelBootImageCmd(const uint8_t* comma if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1425,7 +1425,7 @@ ReturnValue_t PlocSupervisorHandler::prepareSetTimeRefCmd() { if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1435,7 +1435,7 @@ ReturnValue_t PlocSupervisorHandler::prepareDisableHk() { if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1447,7 +1447,7 @@ ReturnValue_t PlocSupervisorHandler::prepareSetBootTimeoutCmd(const uint8_t* com if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1458,7 +1458,7 @@ ReturnValue_t PlocSupervisorHandler::prepareRestartTriesCmd(const uint8_t* comma if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1476,7 +1476,7 @@ ReturnValue_t PlocSupervisorHandler::prepareLatchupConfigCmd(const uint8_t* comm if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); break; } case (supv::DISABLE_LATCHUP_ALERT): { @@ -1485,7 +1485,7 @@ ReturnValue_t PlocSupervisorHandler::prepareLatchupConfigCmd(const uint8_t* comm if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); break; } default: { @@ -1512,7 +1512,7 @@ ReturnValue_t PlocSupervisorHandler::prepareSetAlertLimitCmd(const uint8_t* comm if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1523,7 +1523,7 @@ ReturnValue_t PlocSupervisorHandler::prepareSetAdcEnabledChannelsCmd(const uint8 if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1537,7 +1537,7 @@ ReturnValue_t PlocSupervisorHandler::prepareSetAdcWindowAndStrideCmd(const uint8 if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1549,7 +1549,7 @@ ReturnValue_t PlocSupervisorHandler::prepareSetAdcThresholdCmd(const uint8_t* co if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1563,7 +1563,7 @@ ReturnValue_t PlocSupervisorHandler::prepareRunAutoEmTest(const uint8_t* command if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1581,7 +1581,7 @@ ReturnValue_t PlocSupervisorHandler::prepareWipeMramCmd(const uint8_t* commandDa if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1605,7 +1605,7 @@ ReturnValue_t PlocSupervisorHandler::prepareDumpMramCmd(const uint8_t* commandDa } receivedMramDumpPackets = 0; - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1618,7 +1618,7 @@ ReturnValue_t PlocSupervisorHandler::prepareSetGpioCmd(const uint8_t* commandDat if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1630,11 +1630,15 @@ ReturnValue_t PlocSupervisorHandler::prepareReadGpioCmd(const uint8_t* commandDa if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } -void PlocSupervisorHandler::finishTcPrep() { nextReplyId = supv::ACK_REPORT; } +void PlocSupervisorHandler::finishTcPrep(size_t packetLen) { + nextReplyId = supv::ACK_REPORT; + rawPacket = commandBuffer; + rawPacketLen = packetLen; +} ReturnValue_t PlocSupervisorHandler::prepareSetShutdownTimeoutCmd(const uint8_t* commandData) { uint32_t timeout = 0; @@ -1652,7 +1656,7 @@ ReturnValue_t PlocSupervisorHandler::prepareSetShutdownTimeoutCmd(const uint8_t* if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1666,7 +1670,7 @@ ReturnValue_t PlocSupervisorHandler::prepareLoggingRequest(const uint8_t* comman if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } @@ -1679,7 +1683,7 @@ ReturnValue_t PlocSupervisorHandler::prepareEnableNvmsCommand(const uint8_t* com if (result != RETURN_OK) { return result; } - finishTcPrep(); + finishTcPrep(packet.getFullPacketLen()); return RETURN_OK; } diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index c6476679..ebd059f9 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -287,7 +287,7 @@ class PlocSupervisorHandler : public DeviceHandlerBase { /** * @brief Copies the content of a space packet to the command buffer. */ - void finishTcPrep(); + void finishTcPrep(size_t packetLen); /** * @brief In case an acknowledgment failure reply has been received this function disables diff --git a/tmtc b/tmtc index 7e1eeb85..77a4f493 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 7e1eeb85fcee45c3d421a8e344d3678ec6334873 +Subproject commit 77a4f493050463cad66c4913aa66b67c678ca34a From ec47d7eeef04771ef0f4e15d01a40b9f9de227c2 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 18 Aug 2022 15:32:24 +0200 Subject: [PATCH 23/58] important bugfix for CRC calculation --- .../devicedefinitions/PlocMPSoCDefinitions.h | 27 ++++--- .../PlocSupervisorDefinitions.h | 74 ++++++++++++------- linux/devices/ploc/PlocSupervisorHandler.cpp | 2 +- mission/controller/AcsController.cpp | 2 +- mission/devices/devicedefinitions/SpBase.h | 6 +- 5 files changed, 66 insertions(+), 45 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index aa0f85b8..a293b1f7 100644 --- a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h +++ b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h @@ -259,7 +259,6 @@ class TcMemWrite : public TcBase { : TcBase(params, apid::TC_MEM_WRITE, sequenceCount) {} protected: - ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override { ReturnValue_t result = HasReturnvaluesIF::RETURN_OK; result = lengthCheck(commandDataLen); @@ -270,7 +269,7 @@ class TcMemWrite : public TcBase { *(commandData + MEM_ADDRESS_SIZE) << 8 | *(commandData + MEM_ADDRESS_SIZE + 1); spParams.setPayloadLen(MIN_FIXED_PAYLOAD_LENGTH + memLen * 4); result = checkPayloadLen(); - if(result != HasReturnvaluesIF::RETURN_OK) { + if (result != HasReturnvaluesIF::RETURN_OK) { return result; } std::memcpy(payloadStart, commandData, commandDataLen); @@ -284,16 +283,15 @@ class TcMemWrite : public TcBase { // Min length consists of 4 byte address, 2 byte mem length field, 4 byte data (1 word) static const size_t MIN_COMMAND_DATA_LENGTH = MIN_FIXED_PAYLOAD_LENGTH + 4; - ReturnValue_t lengthCheck(size_t commandDataLen) { if (commandDataLen < MIN_COMMAND_DATA_LENGTH) { - sif::warning << "TcMemWrite: Length " << commandDataLen << " smaller than minimum " << - MIN_COMMAND_DATA_LENGTH << std::endl; + sif::warning << "TcMemWrite: Length " << commandDataLen << " smaller than minimum " + << MIN_COMMAND_DATA_LENGTH << std::endl; return INVALID_LENGTH; } - if(commandDataLen + CRC_SIZE > spParams.maxSize) { - sif::warning << "TcMemWrite: Length " << commandDataLen << " larger than allowed " << - spParams.maxSize - CRC_SIZE << std::endl; + if (commandDataLen + CRC_SIZE > spParams.maxSize) { + sif::warning << "TcMemWrite: Length " << commandDataLen << " larger than allowed " + << spParams.maxSize - CRC_SIZE << std::endl; return INVALID_LENGTH; } return HasReturnvaluesIF::RETURN_OK; @@ -317,7 +315,7 @@ class FlashFopen : public ploc::SpTcBase { size_t nameSize = filename.size(); spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR) + sizeof(accessMode)); ReturnValue_t result = checkPayloadLen(); - if(result != HasReturnvaluesIF::RETURN_OK) { + if (result != HasReturnvaluesIF::RETURN_OK) { return result; } std::memcpy(payloadStart, filename.c_str(), nameSize); @@ -343,7 +341,7 @@ class FlashFclose : public ploc::SpTcBase { size_t nameSize = filename.size(); spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR)); ReturnValue_t result = checkPayloadLen(); - if(result != HasReturnvaluesIF::RETURN_OK) { + if (result != HasReturnvaluesIF::RETURN_OK) { return result; } std::memcpy(payloadStart, filename.c_str(), nameSize); @@ -369,7 +367,7 @@ class TcFlashWrite : public ploc::SpTcBase { } spParams.setPayloadLen(static_cast(writeLen) + 4); result = checkPayloadLen(); - if(result != HasReturnvaluesIF::RETURN_OK) { + if (result != HasReturnvaluesIF::RETURN_OK) { return result; } size_t serializedSize = 0; @@ -403,7 +401,7 @@ class TcFlashDelete : public ploc::SpTcBase { size_t nameSize = filename.size(); spParams.setPayloadLen(nameSize + sizeof(NULL_TERMINATOR)); auto res = checkPayloadLen(); - if(res != HasReturnvaluesIF::RETURN_OK) { + if (res != HasReturnvaluesIF::RETURN_OK) { return res; } std::memcpy(payloadStart, filename.c_str(), nameSize); @@ -460,7 +458,8 @@ class TcReplayStart : public TcBase { static const uint8_t ONCE = 1; ReturnValue_t lengthCheck(size_t commandDataLen) { - if (commandDataLen != COMMAND_DATA_LENGTH or checkPayloadLen() != HasReturnvaluesIF::RETURN_OK) { + if (commandDataLen != COMMAND_DATA_LENGTH or + checkPayloadLen() != HasReturnvaluesIF::RETURN_OK) { sif::warning << "TcReplayStart: Command has invalid length " << commandDataLen << std::endl; return INVALID_LENGTH; } @@ -661,7 +660,7 @@ class TcCamcmdSend : public TcBase { uint16_t dataLen = static_cast(commandDataLen + sizeof(CARRIAGE_RETURN)); spParams.setPayloadLen(sizeof(dataLen) + commandDataLen + sizeof(CARRIAGE_RETURN)); auto res = checkPayloadLen(); - if(res != HasReturnvaluesIF::RETURN_OK) { + if (res != HasReturnvaluesIF::RETURN_OK) { return res; } size_t size = sizeof(dataLen); diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index b576af7e..d6f74909 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -405,7 +405,10 @@ class SetTimeRef : public ploc::SpTcBase { if (res != result::OK) { return res; } - initPacket(time); + res = initPacket(time); + if (res != result::OK) { + return res; + } return calcCrc(); } @@ -414,30 +417,49 @@ class SetTimeRef : public ploc::SpTcBase { static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; static const uint16_t SYNC = 0x8000; - void initPacket(Clock::TimeOfDay_t* time) { - size_t serializedSize = 0; + ReturnValue_t initPacket(Clock::TimeOfDay_t* time) { + size_t serializedSize = 6; uint8_t* dataFieldPtr = payloadStart; uint16_t milliseconds = static_cast(time->usecond / 1000) | SYNC; - SerializeAdapter::serialize(&milliseconds, &dataFieldPtr, &serializedSize, - sizeof(milliseconds), SerializeIF::Endianness::BIG); + ReturnValue_t result = + SerializeAdapter::serialize(&milliseconds, &dataFieldPtr, &serializedSize, spParams.maxSize, + SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } uint8_t second = static_cast(time->second); - SerializeAdapter::serialize(&second, &dataFieldPtr, &serializedSize, - sizeof(time->second), SerializeIF::Endianness::BIG); + result = SerializeAdapter::serialize(&second, &dataFieldPtr, &serializedSize, spParams.maxSize, + SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } uint8_t minute = static_cast(time->minute); - SerializeAdapter::serialize(&minute, &dataFieldPtr, &serializedSize, - sizeof(time->minute), SerializeIF::Endianness::BIG); + result = SerializeAdapter::serialize(&minute, &dataFieldPtr, &serializedSize, spParams.maxSize, + SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } uint8_t hour = static_cast(time->hour); - SerializeAdapter::serialize(&hour, &dataFieldPtr, &serializedSize, sizeof(time->hour), + result = SerializeAdapter::serialize(&hour, &dataFieldPtr, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } uint8_t day = static_cast(time->day); - SerializeAdapter::serialize(&day, &dataFieldPtr, &serializedSize, sizeof(time->day), + result = SerializeAdapter::serialize(&day, &dataFieldPtr, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } uint8_t month = static_cast(time->month); - SerializeAdapter::serialize(&month, &dataFieldPtr, &serializedSize, - sizeof(time->month), SerializeIF::Endianness::BIG); - uint8_t year = static_cast(time->year - 1900); - SerializeAdapter::serialize(&year, &dataFieldPtr, &serializedSize, sizeof(time->year), + result = SerializeAdapter::serialize(&month, &dataFieldPtr, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + uint8_t year = static_cast(time->year - 1900); + return SerializeAdapter::serialize(&year, &dataFieldPtr, &serializedSize, spParams.maxSize, + SerializeIF::Endianness::BIG); } }; @@ -1096,7 +1118,7 @@ class WriteMemory : public ploc::SpTcBase { uint8_t n = 1; ReturnValue_t initPacket(uint8_t memoryId, uint32_t startAddr, uint16_t updateDataLen, - uint8_t* updateData) { + uint8_t* updateData) { size_t serializedSize = 0; uint8_t* data = payloadStart; SerializeAdapter::serialize(&memoryId, &data, &serializedSize, sizeof(memoryId), @@ -1117,7 +1139,7 @@ class WriteMemory : public ploc::SpTcBase { } // To avoid crashes in this unexpected case ReturnValue_t result = checkPayloadLen(); - if(result != HasReturnvaluesIF::RETURN_OK) { + if (result != HasReturnvaluesIF::RETURN_OK) { return result; } std::memcpy(data, updateData, updateDataLen); @@ -1311,38 +1333,38 @@ 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 << "Supervisor acknowledgment report status: Ok" << std::endl; + sif::warning << prefix << "Ok" << std::endl; break; } case StatusCode::BAD_PARAM: { - sif::warning << "Supervisor acknowledgment report status: Bad param" << std::endl; + sif::warning << prefix << "Bad param" << std::endl; break; } case StatusCode::TIMEOUT: { - sif::warning << "Supervisor acknowledgment report status: Timeout" << std::endl; + sif::warning << prefix << "Timeout" << std::endl; break; } case StatusCode::RX_ERROR: { - sif::warning << "Supervisor acknowledgment report status: RX error" << std::endl; + sif::warning << prefix << "RX error" << std::endl; break; } case StatusCode::TX_ERROR: { - sif::warning << "Supervisor acknowledgment report status: TX error" << std::endl; + sif::warning << prefix << "TX error" << std::endl; break; } case StatusCode::HEADER_EMPTY: { - sif::warning << "Supervisor acknowledgment report status: Header empty" << std::endl; + sif::warning << prefix << "Header empty" << std::endl; break; } case StatusCode::DEFAULT_NAK: { - sif::warning << "Supervisor acknowledgment report status: Default code for nak" - << std::endl; + sif::warning << prefix << "Default code for NAK" << std::endl; break; } case StatusCode::ROUTE_PACKET: { - sif::warning << "Supervisor acknowledgment report status: Route packet error" << std::endl; + sif::warning << prefix << "Route packet error" << std::endl; break; } default: diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 6789f9f5..fbbcf3c4 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -907,7 +907,7 @@ ReturnValue_t PlocSupervisorHandler::handleAckReport(const uint8_t* data) { AcknowledgmentReport ack(data, SIZE_ACK_REPORT); result = ack.checkSize(); - if(result != RETURN_OK) { + if (result != RETURN_OK) { return result; } diff --git a/mission/controller/AcsController.cpp b/mission/controller/AcsController.cpp index c9e237bb..48c6f521 100644 --- a/mission/controller/AcsController.cpp +++ b/mission/controller/AcsController.cpp @@ -32,7 +32,7 @@ void AcsController::performControlOperation() { { PoolReadGuard pg(&mgmData); if (pg.getReadResult() == RETURN_OK) { - copyMgmData(); + copyMgmData(); } } } diff --git a/mission/devices/devicedefinitions/SpBase.h b/mission/devices/devicedefinitions/SpBase.h index c3a683cb..82a3c0c7 100644 --- a/mission/devices/devicedefinitions/SpBase.h +++ b/mission/devices/devicedefinitions/SpBase.h @@ -73,12 +73,12 @@ class SpTcBase { ReturnValue_t calcCrc() { /* Calculate crc */ - uint16_t crc = CRC::crc16ccitt(spParams.buf, ccsds::HEADER_LEN + spParams.dataFieldLen - 2); + uint16_t crc = CRC::crc16ccitt(spParams.buf, getFullPacketLen() - 2); /* Add crc to packet data field of space packet */ size_t serializedSize = 0; - return SerializeAdapter::serialize(&crc, &payloadStart, &serializedSize, sizeof(crc), - SerializeIF::Endianness::BIG); + return SerializeAdapter::serialize(&crc, spParams.buf + getFullPacketLen() - 2, &serializedSize, + spParams.maxSize, SerializeIF::Endianness::BIG); } protected: From ba56c72d91481cd4d9f6102dff682baaddc19594 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 18 Aug 2022 15:34:26 +0200 Subject: [PATCH 24/58] simpler way to check crc16 --- linux/devices/ploc/PlocSupervisorHandler.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index fbbcf3c4..1f588299 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -893,9 +893,7 @@ void PlocSupervisorHandler::setExecutionTimeout(DeviceCommandId_t command) { } ReturnValue_t PlocSupervisorHandler::verifyPacket(const uint8_t* start, size_t foundLen) { - uint16_t receivedCrc = *(start + foundLen - 2) << 8 | *(start + foundLen - 1); - uint16_t recalculatedCrc = CRC::crc16ccitt(start, foundLen - 2); - if (receivedCrc != recalculatedCrc) { + if (CRC::crc16ccitt(start, foundLen) != 0) { return SupvReturnValuesIF::CRC_FAILURE; } return RETURN_OK; From 48ef6e6a5c44d91c5eb4ecc4524b3df09d536eb1 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Thu, 18 Aug 2022 15:52:59 +0200 Subject: [PATCH 25/58] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 77a4f493..1f5baabf 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 77a4f493050463cad66c4913aa66b67c678ca34a +Subproject commit 1f5baabf312eb7edc5b0449d443dd5f73054dfa2 From d318ff97817a9fbc63403ad5237f91bf3753da77 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 19 Aug 2022 12:38:37 +0200 Subject: [PATCH 26/58] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 1f5baabf..95b27b88 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 1f5baabf312eb7edc5b0449d443dd5f73054dfa2 +Subproject commit 95b27b889d7d34c13f8586826d3f56f7a216fda8 From 4aad06469d251d43ba7de59b16c9adc7703b0cba Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 19 Aug 2022 12:43:35 +0200 Subject: [PATCH 27/58] tmtc bugfix --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 95b27b88..d8b0d81e 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 95b27b889d7d34c13f8586826d3f56f7a216fda8 +Subproject commit d8b0d81ef3165325284956456138b529f6e9fae0 From 0ea993e16b59912b181795f62fc6c40efb95e614 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 19 Aug 2022 15:49:22 +0200 Subject: [PATCH 28/58] some bugfixes --- .../devicedefinitions/PlocMPSoCDefinitions.h | 2 +- linux/devices/ploc/PlocMPSoCHandler.cpp | 34 ++++++++++--------- linux/devices/ploc/PlocMPSoCHandler.h | 2 +- mission/controller/AcsController.h | 27 +++++++-------- .../AcsCtrlDefinitions.h | 13 +++---- tmtc | 2 +- 6 files changed, 39 insertions(+), 41 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index a293b1f7..0002695d 100644 --- a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h +++ b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h @@ -143,7 +143,7 @@ class TcBase : public ploc::SpTcBase, public MPSoCReturnValuesIF { virtual ~TcBase() = default; // Initial length field of space packet. Will always be updated when packet is created. - static const uint16_t INIT_LENGTH = 1; + static const uint16_t INIT_LENGTH = 2; /** * @brief Constructor diff --git a/linux/devices/ploc/PlocMPSoCHandler.cpp b/linux/devices/ploc/PlocMPSoCHandler.cpp index b3eea536..7bfa09d3 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.cpp +++ b/linux/devices/ploc/PlocMPSoCHandler.cpp @@ -410,7 +410,7 @@ ReturnValue_t PlocMPSoCHandler::prepareTcMemWrite(const uint8_t* commandData, sequenceCount--; return result; } - finishTcPrep(); + finishTcPrep(tcMemWrite.getFullPacketLen()); return RETURN_OK; } @@ -424,7 +424,7 @@ ReturnValue_t PlocMPSoCHandler::prepareTcMemRead(const uint8_t* commandData, sequenceCount--; return result; } - finishTcPrep(); + finishTcPrep(tcMemRead.getFullPacketLen()); tmMemReadReport.rememberRequestedSize = tcMemRead.getMemLen() * 4 + TmMemReadReport::FIX_SIZE; return RETURN_OK; } @@ -443,7 +443,7 @@ ReturnValue_t PlocMPSoCHandler::prepareTcFlashDelete(const uint8_t* commandData, sequenceCount--; return result; } - finishTcPrep(); + finishTcPrep(tcFlashDelete.getFullPacketLen()); return RETURN_OK; } @@ -457,7 +457,7 @@ ReturnValue_t PlocMPSoCHandler::prepareTcReplayStart(const uint8_t* commandData, sequenceCount--; return result; } - finishTcPrep(); + finishTcPrep(tcReplayStart.getFullPacketLen()); return RETURN_OK; } @@ -470,7 +470,7 @@ ReturnValue_t PlocMPSoCHandler::prepareTcReplayStop() { sequenceCount--; return result; } - finishTcPrep(); + finishTcPrep(tcReplayStop.getFullPacketLen()); return RETURN_OK; } @@ -484,7 +484,7 @@ ReturnValue_t PlocMPSoCHandler::prepareTcDownlinkPwrOn(const uint8_t* commandDat sequenceCount--; return result; } - finishTcPrep(); + finishTcPrep(tcDownlinkPwrOn.getFullPacketLen()); return RETURN_OK; } @@ -497,7 +497,7 @@ ReturnValue_t PlocMPSoCHandler::prepareTcDownlinkPwrOff() { sequenceCount--; return result; } - finishTcPrep(); + finishTcPrep(tcDownlinkPwrOff.getFullPacketLen()); return RETURN_OK; } @@ -511,7 +511,7 @@ ReturnValue_t PlocMPSoCHandler::prepareTcReplayWriteSequence(const uint8_t* comm sequenceCount--; return result; } - finishTcPrep(); + finishTcPrep(tcReplayWriteSeq.getFullPacketLen()); return RETURN_OK; } @@ -524,7 +524,7 @@ ReturnValue_t PlocMPSoCHandler::prepareTcModeReplay() { sequenceCount--; return result; } - finishTcPrep(); + finishTcPrep(tcModeReplay.getFullPacketLen()); return RETURN_OK; } @@ -537,7 +537,7 @@ ReturnValue_t PlocMPSoCHandler::prepareTcModeIdle() { sequenceCount--; return result; } - finishTcPrep(); + finishTcPrep(tcModeIdle.getFullPacketLen()); return RETURN_OK; } @@ -551,17 +551,19 @@ ReturnValue_t PlocMPSoCHandler::prepareTcCamCmdSend(const uint8_t* commandData, sequenceCount--; return result; } - finishTcPrep(); + finishTcPrep(tcCamCmdSend.getFullPacketLen()); nextReplyId = mpsoc::TM_CAM_CMD_RPT; return RETURN_OK; } -void PlocMPSoCHandler::finishTcPrep() { nextReplyId = mpsoc::ACK_REPORT; } +void PlocMPSoCHandler::finishTcPrep(size_t packetLen) { + nextReplyId = mpsoc::ACK_REPORT; + rawPacket = commandBuffer; + rawPacketLen = packetLen; +} ReturnValue_t PlocMPSoCHandler::verifyPacket(const uint8_t* start, size_t foundLen) { - uint16_t receivedCrc = *(start + foundLen - 2) << 8 | *(start + foundLen - 1); - uint16_t recalculatedCrc = CRC::crc16ccitt(start, foundLen - 2); - if (receivedCrc != recalculatedCrc) { + if (CRC::crc16ccitt(start, foundLen) != 0) { return MPSoCReturnValuesIF::CRC_FAILURE; } return RETURN_OK; @@ -683,7 +685,7 @@ ReturnValue_t PlocMPSoCHandler::handleCamCmdRpt(const uint8_t* data) { reinterpret_cast(dataFieldPtr), tmCamCmdRpt.rememberSpacePacketSize - mpsoc::SPACE_PACKET_HEADER_SIZE - sizeof(uint16_t) - 3); #if OBSW_DEBUG_PLOC_MPSOC == 1 - uint8_t ackValue = *(packet.getPacketData() + packet.getPacketDataLength() - 2); + uint8_t ackValue = *(packetReader.getPacketData() + packetReader.getPacketDataLen() - 2); sif::info << "PlocMPSoCHandler: CamCmdRpt message: " << camCmdRptMsg << std::endl; sif::info << "PlocMPSoCHandler: CamCmdRpt Ack value: 0x" << std::hex << static_cast(ackValue) << std::endl; diff --git a/linux/devices/ploc/PlocMPSoCHandler.h b/linux/devices/ploc/PlocMPSoCHandler.h index 4325f8ee..05c2e902 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.h +++ b/linux/devices/ploc/PlocMPSoCHandler.h @@ -172,7 +172,7 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF { ReturnValue_t prepareTcReplayWriteSequence(const uint8_t* commandData, size_t commandDataLen); ReturnValue_t prepareTcCamCmdSend(const uint8_t* commandData, size_t commandDataLen); ReturnValue_t prepareTcModeIdle(); - void finishTcPrep(); + void finishTcPrep(size_t packetLen); /** * @brief This function checks the crc of the received PLOC reply. diff --git a/mission/controller/AcsController.h b/mission/controller/AcsController.h index 4fa00283..358b1871 100644 --- a/mission/controller/AcsController.h +++ b/mission/controller/AcsController.h @@ -55,21 +55,20 @@ class AcsController : public ExtendedControllerBase { void copyMgmData(); - // Sun Sensors - std::array susSets { - SUS::SusDataset(objects::SUS_0_N_LOC_XFYFZM_PT_XF), - SUS::SusDataset(objects::SUS_1_N_LOC_XBYFZM_PT_XB), - SUS::SusDataset(objects::SUS_2_N_LOC_XFYBZB_PT_YB), - SUS::SusDataset(objects::SUS_3_N_LOC_XFYBZF_PT_YF), - SUS::SusDataset(objects::SUS_4_N_LOC_XMYFZF_PT_ZF), - SUS::SusDataset(objects::SUS_5_N_LOC_XFYMZB_PT_ZB), - SUS::SusDataset(objects::SUS_6_R_LOC_XFYBZM_PT_XF), - SUS::SusDataset(objects::SUS_7_R_LOC_XBYBZM_PT_XB), - SUS::SusDataset(objects::SUS_8_R_LOC_XBYBZB_PT_YB), - SUS::SusDataset(objects::SUS_9_R_LOC_XBYBZB_PT_YF), - SUS::SusDataset(objects::SUS_10_N_LOC_XMYBZF_PT_ZF), - SUS::SusDataset(objects::SUS_11_R_LOC_XBYMZB_PT_ZB), + std::array susSets{ + SUS::SusDataset(objects::SUS_0_N_LOC_XFYFZM_PT_XF), + SUS::SusDataset(objects::SUS_1_N_LOC_XBYFZM_PT_XB), + SUS::SusDataset(objects::SUS_2_N_LOC_XFYBZB_PT_YB), + SUS::SusDataset(objects::SUS_3_N_LOC_XFYBZF_PT_YF), + SUS::SusDataset(objects::SUS_4_N_LOC_XMYFZF_PT_ZF), + SUS::SusDataset(objects::SUS_5_N_LOC_XFYMZB_PT_ZB), + SUS::SusDataset(objects::SUS_6_R_LOC_XFYBZM_PT_XF), + SUS::SusDataset(objects::SUS_7_R_LOC_XBYBZM_PT_XB), + SUS::SusDataset(objects::SUS_8_R_LOC_XBYBZB_PT_YB), + SUS::SusDataset(objects::SUS_9_R_LOC_XBYBZB_PT_YF), + SUS::SusDataset(objects::SUS_10_N_LOC_XMYBZF_PT_ZF), + SUS::SusDataset(objects::SUS_11_R_LOC_XBYMZB_PT_ZB), }; // Initial delay to make sure all pool variables have been initialized their owners diff --git a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h index c3a97f0d..bafe778f 100644 --- a/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h +++ b/mission/controller/controllerdefinitions/AcsCtrlDefinitions.h @@ -8,10 +8,7 @@ namespace acsctrl { -enum SetIds : uint32_t { - MGM_SENSOR_DATA, - SUS_SENSOR_DATA -}; +enum SetIds : uint32_t { MGM_SENSOR_DATA, SUS_SENSOR_DATA }; enum PoolIds : lp_id_t { MGM_0_LIS3_UT, @@ -63,11 +60,11 @@ class MgmData : public StaticLocalDataSet { private: }; - -class SusData: public StaticLocalDataSet { -public: +class SusData : public StaticLocalDataSet { + public: SusData(HasLocalDataPoolIF* hkOwner) : StaticLocalDataSet(hkOwner, SUS_SENSOR_DATA) {} -private: + + private: }; } // namespace acsctrl diff --git a/tmtc b/tmtc index d8b0d81e..00e99292 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit d8b0d81ef3165325284956456138b529f6e9fae0 +Subproject commit 00e99292cc158a347f485507537fa5b63262243b From ad3bdbcf96aa1ba5f89eef07e51fc49793b787c2 Mon Sep 17 00:00:00 2001 From: meierj Date: Sat, 20 Aug 2022 10:26:19 +0200 Subject: [PATCH 29/58] mode check for commands executed by supervisor helper --- linux/devices/ploc/PlocSupervisorHandler.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 1f588299..3d00d440 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -104,6 +104,11 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, return SupvReturnValuesIF::SUPV_HELPER_EXECUTING; } + result = acceptExternalDeviceCommands(); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + switch (actionId) { case PERFORM_UPDATE: { if (size > config::MAX_PATH_SIZE + config::MAX_FILENAME_SIZE) { From c85035c62e5f0af1232b6a6b9086c76ee8de4249 Mon Sep 17 00:00:00 2001 From: meierj Date: Sat, 20 Aug 2022 10:27:43 +0200 Subject: [PATCH 30/58] bugfixes in tc packaging classes --- .../devicedefinitions/PlocSupervisorDefinitions.h | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index d6f74909..b350a6a9 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -1069,9 +1069,12 @@ class CheckMemory : public ploc::SpTcBase { size_t serLen = 0; SerializeAdapter::serialize(&memoryId, &data, &serLen, sizeof(memoryId), SerializeIF::Endianness::BIG); + serLen = 0; SerializeAdapter::serialize(&n, &data, &serLen, sizeof(n), SerializeIF::Endianness::BIG); + serLen = 0; SerializeAdapter::serialize(&startAddress, &data, &serLen, sizeof(startAddress), SerializeIF::Endianness::BIG); + serLen = 0; SerializeAdapter::serialize(&length, &data, &serLen, sizeof(length), SerializeIF::Endianness::BIG); } @@ -1123,10 +1126,13 @@ class WriteMemory : public ploc::SpTcBase { uint8_t* data = payloadStart; SerializeAdapter::serialize(&memoryId, &data, &serializedSize, sizeof(memoryId), SerializeIF::Endianness::BIG); + serializedSize = 0; SerializeAdapter::serialize(&n, &data, &serializedSize, sizeof(n), SerializeIF::Endianness::BIG); + serializedSize = 0; SerializeAdapter::serialize(&startAddr, &data, &serializedSize, sizeof(startAddr), SerializeIF::Endianness::BIG); + serializedSize = 0; SerializeAdapter::serialize(&updateDataLen, &data, &serializedSize, sizeof(updateDataLen), SerializeIF::Endianness::BIG); if (updateDataLen % 2 != 0) { @@ -1148,7 +1154,7 @@ class WriteMemory : public ploc::SpTcBase { }; /** - * @brief This class can be used to package the update available or update verify command. + * @brief This class can be used to package erase memory command */ class EraseMemory : public ploc::SpTcBase { public: @@ -1180,6 +1186,7 @@ class EraseMemory : public ploc::SpTcBase { uint8_t* data = payloadStart; SerializeAdapter::serialize(&memoryId, &data, &serializedSize, sizeof(memoryId), SerializeIF::Endianness::BIG); + serializedSize = 0; SerializeAdapter::serialize(&n, &data, &serializedSize, sizeof(n), SerializeIF::Endianness::BIG); serializedSize = 0; From f9061d54945892493c7675e59e03b63dc2d8c22b Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Fri, 19 Aug 2022 21:41:24 +0200 Subject: [PATCH 31/58] fix --- linux/devices/ploc/PlocMPSoCHandler.cpp | 4 ++++ tmtc | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/linux/devices/ploc/PlocMPSoCHandler.cpp b/linux/devices/ploc/PlocMPSoCHandler.cpp index 7bfa09d3..a0fd8f53 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.cpp +++ b/linux/devices/ploc/PlocMPSoCHandler.cpp @@ -685,7 +685,11 @@ ReturnValue_t PlocMPSoCHandler::handleCamCmdRpt(const uint8_t* data) { reinterpret_cast(dataFieldPtr), tmCamCmdRpt.rememberSpacePacketSize - mpsoc::SPACE_PACKET_HEADER_SIZE - sizeof(uint16_t) - 3); #if OBSW_DEBUG_PLOC_MPSOC == 1 +<<<<<<< HEAD uint8_t ackValue = *(packetReader.getPacketData() + packetReader.getPacketDataLen() - 2); +======= + uint8_t ackValue = *(packetReader.getFullData() + packetReader.getFullPacketLen() - 2); +>>>>>>> 9eb21079 (fix) sif::info << "PlocMPSoCHandler: CamCmdRpt message: " << camCmdRptMsg << std::endl; sif::info << "PlocMPSoCHandler: CamCmdRpt Ack value: 0x" << std::hex << static_cast(ackValue) << std::endl; diff --git a/tmtc b/tmtc index 00e99292..1b39bb2a 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 00e99292cc158a347f485507537fa5b63262243b +Subproject commit 1b39bb2ad2421db89487b4ea352edbd4d420b9b1 From 8ea6df273d70ce342e5c413780bfd252d87e065d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 20 Aug 2022 01:45:49 +0200 Subject: [PATCH 32/58] moved a size check --- .../PlocSupervisorDefinitions.h | 27 +++++++++---------- 1 file changed, 13 insertions(+), 14 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index b350a6a9..afbc99b9 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -1124,22 +1124,8 @@ class WriteMemory : public ploc::SpTcBase { uint8_t* updateData) { size_t serializedSize = 0; uint8_t* data = payloadStart; - SerializeAdapter::serialize(&memoryId, &data, &serializedSize, sizeof(memoryId), - SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&n, &data, &serializedSize, sizeof(n), - SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&startAddr, &data, &serializedSize, sizeof(startAddr), - SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&updateDataLen, &data, &serializedSize, sizeof(updateDataLen), - SerializeIF::Endianness::BIG); if (updateDataLen % 2 != 0) { spParams.setPayloadLen(META_DATA_LENGTH + updateDataLen + 1); - // 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; } else { spParams.setPayloadLen(META_DATA_LENGTH + updateDataLen); } @@ -1148,7 +1134,20 @@ class WriteMemory : public ploc::SpTcBase { if (result != HasReturnvaluesIF::RETURN_OK) { return result; } + SerializeAdapter::serialize(&memoryId, &data, &serializedSize, sizeof(memoryId), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&n, &data, &serializedSize, sizeof(n), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&startAddr, &data, &serializedSize, sizeof(startAddr), + SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&updateDataLen, &data, &serializedSize, sizeof(updateDataLen), + SerializeIF::Endianness::BIG); std::memcpy(data, updateData, updateDataLen); + 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; + } return HasReturnvaluesIF::RETURN_OK; } }; From 5aa0b3530a0026a0f0270eb020c487f1e2c54afa Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 20 Aug 2022 12:11:08 +0200 Subject: [PATCH 33/58] bugfixes --- .../devicedefinitions/PlocMPSoCDefinitions.h | 8 ++-- .../PlocSupervisorDefinitions.h | 42 ++++++++----------- linux/devices/ploc/PlocSupvHelper.cpp | 9 ++++ linux/devices/ploc/PlocSupvHelper.h | 4 +- 4 files changed, 33 insertions(+), 30 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h index 0002695d..180ee907 100644 --- a/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h +++ b/linux/devices/devicedefinitions/PlocMPSoCDefinitions.h @@ -370,8 +370,8 @@ class TcFlashWrite : public ploc::SpTcBase { if (result != HasReturnvaluesIF::RETURN_OK) { return result; } - size_t serializedSize = 0; - result = SerializeAdapter::serialize(&writeLen, payloadStart, &serializedSize, sizeof(writeLen), + size_t serializedSize = ccsds::HEADER_LEN; + result = SerializeAdapter::serialize(&writeLen, payloadStart, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); if (result != HasReturnvaluesIF::RETURN_OK) { return result; @@ -663,8 +663,8 @@ class TcCamcmdSend : public TcBase { if (res != HasReturnvaluesIF::RETURN_OK) { return res; } - size_t size = sizeof(dataLen); - SerializeAdapter::serialize(&dataLen, payloadStart, &size, sizeof(dataLen), + size_t size = ccsds::HEADER_LEN; + SerializeAdapter::serialize(&dataLen, payloadStart, &size, spParams.maxSize, SerializeIF::Endianness::BIG); std::memcpy(payloadStart + sizeof(dataLen), commandData, commandDataLen); *(payloadStart + sizeof(dataLen) + commandDataLen) = CARRIAGE_RETURN; diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index afbc99b9..de05c9e9 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -721,11 +721,11 @@ class SetAdcWindowAndStride : public ploc::SpTcBase { static const uint16_t CRC_OFFSET = DATA_FIELD_LENGTH - 2; void initPacket(uint16_t windowSize, uint16_t stridingStepSize) { - size_t serializedSize = 0; + size_t serializedSize = 6; uint8_t* data = payloadStart; - SerializeAdapter::serialize(&windowSize, &data, &serializedSize, sizeof(windowSize), + SerializeAdapter::serialize(&windowSize, &data, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); - SerializeAdapter::serialize(&stridingStepSize, &data, &serializedSize, sizeof(stridingStepSize), + SerializeAdapter::serialize(&stridingStepSize, &data, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); } }; @@ -1066,16 +1066,13 @@ class CheckMemory : public ploc::SpTcBase { void initPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { uint8_t* data = payloadStart; - size_t serLen = 0; - SerializeAdapter::serialize(&memoryId, &data, &serLen, sizeof(memoryId), + size_t serLen = 6; + SerializeAdapter::serialize(&memoryId, &data, &serLen, spParams.maxSize, SerializeIF::Endianness::BIG); - serLen = 0; - SerializeAdapter::serialize(&n, &data, &serLen, sizeof(n), SerializeIF::Endianness::BIG); - serLen = 0; - SerializeAdapter::serialize(&startAddress, &data, &serLen, sizeof(startAddress), + SerializeAdapter::serialize(&n, &data, &serLen, spParams.maxSize, SerializeIF::Endianness::BIG); + SerializeAdapter::serialize(&startAddress, &data, &serLen, spParams.maxSize, SerializeIF::Endianness::BIG); - serLen = 0; - SerializeAdapter::serialize(&length, &data, &serLen, sizeof(length), + SerializeAdapter::serialize(&length, &data, &serLen, spParams.maxSize, SerializeIF::Endianness::BIG); } }; @@ -1122,7 +1119,6 @@ class WriteMemory : public ploc::SpTcBase { ReturnValue_t initPacket(uint8_t memoryId, uint32_t startAddr, uint16_t updateDataLen, uint8_t* updateData) { - size_t serializedSize = 0; uint8_t* data = payloadStart; if (updateDataLen % 2 != 0) { spParams.setPayloadLen(META_DATA_LENGTH + updateDataLen + 1); @@ -1134,13 +1130,14 @@ class WriteMemory : public ploc::SpTcBase { if (result != HasReturnvaluesIF::RETURN_OK) { return result; } - SerializeAdapter::serialize(&memoryId, &data, &serializedSize, sizeof(memoryId), + size_t serializedSize = 6; + SerializeAdapter::serialize(&memoryId, &data, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); - SerializeAdapter::serialize(&n, &data, &serializedSize, sizeof(n), + SerializeAdapter::serialize(&n, &data, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); - SerializeAdapter::serialize(&startAddr, &data, &serializedSize, sizeof(startAddr), + SerializeAdapter::serialize(&startAddr, &data, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); - SerializeAdapter::serialize(&updateDataLen, &data, &serializedSize, sizeof(updateDataLen), + SerializeAdapter::serialize(&updateDataLen, &data, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); std::memcpy(data, updateData, updateDataLen); if (updateDataLen % 2 != 0) { @@ -1181,18 +1178,15 @@ class EraseMemory : public ploc::SpTcBase { uint32_t length = 0; void initPacket(uint8_t memoryId, uint32_t startAddress, uint32_t length) { - size_t serializedSize = 0; uint8_t* data = payloadStart; - SerializeAdapter::serialize(&memoryId, &data, &serializedSize, sizeof(memoryId), + size_t serializedSize = 6; + SerializeAdapter::serialize(&memoryId, &data, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&n, &data, &serializedSize, sizeof(n), + SerializeAdapter::serialize(&n, &data, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&startAddress, &data, &serializedSize, sizeof(startAddress), + SerializeAdapter::serialize(&startAddress, &data, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); - serializedSize = 0; - SerializeAdapter::serialize(&length, &data, &serializedSize, sizeof(length), + SerializeAdapter::serialize(&length, &data, &serializedSize, spParams.maxSize, SerializeIF::Endianness::BIG); } }; diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 25566b11..de1fae0f 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -161,26 +161,32 @@ void PlocSupvHelper::stopProcess() { terminate = true; } ReturnValue_t PlocSupvHelper::performUpdate() { ReturnValue_t result = RETURN_OK; + sif::info << "PlocSupvHelper::performUpdate: Calculating Image CRC" << std::endl; result = calcImageCrc(); if (result != RETURN_OK) { return result; } + sif::info << "PlocSupvHelper::performUpdate: Selecting Memory" << std::endl; result = selectMemory(); if (result != RETURN_OK) { return result; } + sif::info << "PlocSupvHelper::performUpdate: Preparing Update" << std::endl; result = prepareUpdate(); if (result != RETURN_OK) { return result; } + sif::info << "PlocSupvHelper::performUpdate: Erasing Memory" << std::endl; result = eraseMemory(); if (result != RETURN_OK) { return result; } + sif::info << "PlocSupvHelper::performUpdate: Writing Update Packets" << std::endl; result = writeUpdatePackets(); if (result != RETURN_OK) { return result; } + sif::info << "PlocSupvHelper::performUpdate: Memory Check" << std::endl; result = handleCheckMemoryCommand(); if (result != RETURN_OK) { return result; @@ -317,6 +323,9 @@ ReturnValue_t PlocSupvHelper::prepareUpdate() { resetSpParams(); supv::ApidOnlyPacket packet(spParams, supv::APID_PREPARE_UPDATE); result = packet.buildPacket(); + if (result != RETURN_OK) { + return result; + } result = handlePacketTransmission(packet, PREPARE_UPDATE_EXECUTION_REPORT); if (result != RETURN_OK) { return result; diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index c17521d9..66b5d00a 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -178,11 +178,11 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha #ifdef XIPHOS_Q7S SdCardManager* sdcMan = nullptr; #endif - uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]; + uint8_t commandBuffer[supv::MAX_COMMAND_SIZE]{}; SpacePacketCreator creator; ploc::SpTcParams spParams = ploc::SpTcParams(creator); - std::array tmBuf; + std::array tmBuf{}; bool terminate = false; From f2190f8aa1fc0103681d62a7f6d9e94b00e51c28 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 20 Aug 2022 12:24:24 +0200 Subject: [PATCH 34/58] resolve merge conflict --- linux/devices/ploc/PlocMPSoCHandler.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/linux/devices/ploc/PlocMPSoCHandler.cpp b/linux/devices/ploc/PlocMPSoCHandler.cpp index a0fd8f53..c56ada07 100644 --- a/linux/devices/ploc/PlocMPSoCHandler.cpp +++ b/linux/devices/ploc/PlocMPSoCHandler.cpp @@ -685,11 +685,7 @@ ReturnValue_t PlocMPSoCHandler::handleCamCmdRpt(const uint8_t* data) { reinterpret_cast(dataFieldPtr), tmCamCmdRpt.rememberSpacePacketSize - mpsoc::SPACE_PACKET_HEADER_SIZE - sizeof(uint16_t) - 3); #if OBSW_DEBUG_PLOC_MPSOC == 1 -<<<<<<< HEAD - uint8_t ackValue = *(packetReader.getPacketData() + packetReader.getPacketDataLen() - 2); -======= uint8_t ackValue = *(packetReader.getFullData() + packetReader.getFullPacketLen() - 2); ->>>>>>> 9eb21079 (fix) sif::info << "PlocMPSoCHandler: CamCmdRpt message: " << camCmdRptMsg << std::endl; sif::info << "PlocMPSoCHandler: CamCmdRpt Ack value: 0x" << std::hex << static_cast(ackValue) << std::endl; From c094b45fb4790d79527202f3008d9b28f7b3f788 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 20 Aug 2022 20:26:25 +0200 Subject: [PATCH 35/58] percent progress event And some changes to allow restarting from the middle --- linux/devices/ploc/PlocSupvHelper.cpp | 55 ++++++++++++++------------- linux/devices/ploc/PlocSupvHelper.h | 9 ++++- tmtc | 2 +- 3 files changed, 38 insertions(+), 28 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index de1fae0f..c5876793 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -1,5 +1,6 @@ #include "PlocSupvHelper.h" +#include #include #include @@ -98,8 +99,8 @@ ReturnValue_t PlocSupvHelper::setComIF(UartComIF* uartComIF_) { void PlocSupvHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; } -ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId, - uint32_t startAddress) { +ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId, uint32_t startAddress, + size_t startBytesWritten, uint16_t initSeqCount) { ReturnValue_t result = RETURN_OK; #ifdef XIPHOS_Q7S result = FilesystemHelper::checkPath(file); @@ -125,10 +126,11 @@ ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId, update.length = getFileSize(update.file); update.memoryId = memoryId; update.startAddress = startAddress; + update.progressPercent = 0; update.remainingSize = update.length; - update.bytesWritten = 0; + update.bytesWritten = startBytesWritten; update.packetNum = 1; - update.sequenceCount = 1; + update.sequenceCount = initSeqCount; internalState = InternalState::UPDATE; uartComIF->flushUartTxAndRxBuf(comCookie); semaphore.release(); @@ -181,17 +183,7 @@ ReturnValue_t PlocSupvHelper::performUpdate() { if (result != RETURN_OK) { return result; } - sif::info << "PlocSupvHelper::performUpdate: Writing Update Packets" << std::endl; - result = writeUpdatePackets(); - if (result != RETURN_OK) { - return result; - } - sif::info << "PlocSupvHelper::performUpdate: Memory Check" << std::endl; - result = handleCheckMemoryCommand(); - if (result != RETURN_OK) { - return result; - } - return result; + return updateOperation(); } ReturnValue_t PlocSupvHelper::continueUpdate() { @@ -199,15 +191,17 @@ ReturnValue_t PlocSupvHelper::continueUpdate() { if (result != RETURN_OK) { return result; } - result = writeUpdatePackets(); + return updateOperation(); +} + +ReturnValue_t PlocSupvHelper::updateOperation() { + sif::info << "PlocSupvHelper::performUpdate: Writing Update Packets" << std::endl; + auto result = writeUpdatePackets(); if (result != RETURN_OK) { return result; } - result = handleCheckMemoryCommand(); - if (result != RETURN_OK) { - return result; - } - return result; + sif::info << "PlocSupvHelper::performUpdate: Memory Check" << std::endl; + return handleCheckMemoryCommand(); } ReturnValue_t PlocSupvHelper::writeUpdatePackets() { @@ -216,7 +210,7 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { ProgressPrinter progressPrinter("Supervisor update", update.length, ProgressPrinter::HALF_PERCENT); #endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ - uint8_t tempData[supv::WriteMemory::CHUNK_MAX]; + uint8_t tempData[supv::WriteMemory::CHUNK_MAX + 1]{}; std::ifstream file(update.file, std::ifstream::binary); uint16_t dataLength = 0; ccsds::SequenceFlags seqFlags; @@ -232,7 +226,7 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { dataLength = static_cast(update.remainingSize); } if (file.is_open()) { - file.seekg(update.bytesWritten, file.beg); + file.seekg(update.bytesWritten, std::ios::beg); file.read(reinterpret_cast(tempData), dataLength); if (!file) { sif::warning << "PlocSupvHelper::performUpdate: Read only " << file.gcount() << " of " @@ -252,22 +246,31 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { } resetSpParams(); supv::WriteMemory packet(spParams); - result = packet.buildPacket(seqFlags, update.sequenceCount++, update.memoryId, + result = packet.buildPacket(seqFlags, update.sequenceCount, update.memoryId, update.startAddress + update.bytesWritten, dataLength, tempData); if (result != RETURN_OK) { - update.sequenceCount--; triggerEvent(WRITE_MEMORY_FAILED, update.packetNum); return result; } result = handlePacketTransmission(packet); if (result != RETURN_OK) { - update.sequenceCount--; triggerEvent(WRITE_MEMORY_FAILED, update.packetNum); return result; } + uint8_t progPercent = + static_cast(std::floor(static_cast(update.bytesWritten) / update.length)); + if (progPercent > update.progressPercent) { + update.progressPercent = progPercent; + if (progPercent % 5 == 0) { + // Useful to allow restarting the update + triggerEvent(SUPV_UPDATE_PROGRESS, update.bytesWritten, update.sequenceCount); + } + } + update.sequenceCount++; update.remainingSize -= dataLength; update.packetNum += 1; update.bytesWritten += dataLength; + #if OBSW_DEBUG_PLOC_SUPERVISOR == 1 progressPrinter.print(update.bytesWritten); #endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 66b5d00a..0e53a9b6 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -89,6 +89,10 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha static const Event SUPV_REPLY_SIZE_MISSMATCH = MAKE_EVENT(20, severity::LOW); static const Event SUPV_REPLY_CRC_MISSMATCH = MAKE_EVENT(21, severity::LOW); + //! [EXPORT] : [COMMENT] Will be triggered every 5 percent of the update progress. + //! P1: Bytes written, P2: Sequence Count + static constexpr Event SUPV_UPDATE_PROGRESS = MAKE_EVENT(22, severity::INFO); + PlocSupvHelper(object_id_t objectId); virtual ~PlocSupvHelper(); @@ -107,7 +111,8 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha * * @return RETURN_OK if successful, otherwise error return value */ - ReturnValue_t startUpdate(std::string file, uint8_t memoryId, uint32_t startAddress); + ReturnValue_t startUpdate(std::string file, uint8_t memoryId, uint32_t startAddress, + size_t startBytesWritten = 0, uint16_t initSeqCount = 1); /** * @brief This initiate the continuation of a failed update. @@ -157,6 +162,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha size_t bytesWritten; uint32_t packetNum; uint16_t sequenceCount; + uint8_t progressPercent; }; struct Update update; @@ -200,6 +206,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha ReturnValue_t performUpdate(); ReturnValue_t continueUpdate(); + ReturnValue_t updateOperation(); ReturnValue_t writeUpdatePackets(); ReturnValue_t performEventBufferRequest(); ReturnValue_t handlePacketTransmission(ploc::SpTcBase& packet, diff --git a/tmtc b/tmtc index 1b39bb2a..00e99292 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 1b39bb2ad2421db89487b4ea352edbd4d420b9b1 +Subproject commit 00e99292cc158a347f485507537fa5b63262243b From 47ebf3d8cc363b54cf6768b0a59be7b0a09ccaae Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sat, 20 Aug 2022 22:52:48 +0200 Subject: [PATCH 36/58] allow starting update in the middle --- linux/devices/ploc/PlocSupervisorHandler.cpp | 44 +++++++++++------ linux/devices/ploc/PlocSupervisorHandler.h | 11 ++++- linux/devices/ploc/PlocSupvHelper.cpp | 51 +++++++++++--------- linux/devices/ploc/PlocSupvHelper.h | 11 +++-- 4 files changed, 73 insertions(+), 44 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 3d00d440..1ad77883 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -114,14 +114,13 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, if (size > config::MAX_PATH_SIZE + config::MAX_FILENAME_SIZE) { return SupvReturnValuesIF::FILENAME_TOO_LONG; } - std::string file = ""; - uint8_t memoryId = 0; - uint32_t startAddress = 0; - result = extractUpdateCommand(data, size, &file, &memoryId, &startAddress); + UpdateParams params; + result = extractUpdateCommand(data, size, params); if (result != RETURN_OK) { return result; } - result = supvHelper->startUpdate(file, memoryId, startAddress); + result = supvHelper->performUpdate(params.file, params.memId, params.startAddr, + params.bytesWritten, params.seqCount); if (result != RETURN_OK) { return result; } @@ -1974,24 +1973,23 @@ ReturnValue_t PlocSupervisorHandler::getTimeStampString(std::string& timeStamp) } ReturnValue_t PlocSupervisorHandler::extractUpdateCommand(const uint8_t* commandData, size_t size, - std::string* file, uint8_t* memoryId, - uint32_t* startAddress) { + UpdateParams& params) { ReturnValue_t result = RETURN_OK; - if (size > (config::MAX_FILENAME_SIZE + config::MAX_PATH_SIZE + sizeof(*memoryId)) + - sizeof(*startAddress)) { + if (size > (config::MAX_FILENAME_SIZE + config::MAX_PATH_SIZE + sizeof(params.memId)) + + sizeof(params.startAddr)) { sif::warning << "PlocSupervisorHandler::extractUpdateCommand: Data size too big" << std::endl; return SupvReturnValuesIF::INVALID_LENGTH; } - *file = std::string(reinterpret_cast(commandData)); - if (file->size() > (config::MAX_FILENAME_SIZE + config::MAX_PATH_SIZE)) { + 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; } - *memoryId = *(commandData + file->size() + SIZE_NULL_TERMINATOR); + params.memId = *(commandData + params.file.size() + SIZE_NULL_TERMINATOR); const uint8_t* startAddressPtr = - commandData + file->size() + SIZE_NULL_TERMINATOR + sizeof(*memoryId); - size_t remainingSize = 4; - result = SerializeAdapter::deSerialize(startAddress, startAddressPtr, &remainingSize, + commandData + params.file.size() + SIZE_NULL_TERMINATOR + sizeof(params.memId); + size_t remainingSize = 10; + result = SerializeAdapter::deSerialize(¶ms.startAddr, &startAddressPtr, &remainingSize, SerializeIF::Endianness::BIG); if (result != RETURN_OK) { sif::warning @@ -1999,6 +1997,22 @@ ReturnValue_t PlocSupervisorHandler::extractUpdateCommand(const uint8_t* command << std::endl; return result; } + result = SerializeAdapter::deSerialize(¶ms.bytesWritten, &startAddressPtr, &remainingSize, + SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + sif::warning << "PlocSupervisorHandler::extractUpdateCommand: Failed to deserialize bytes " + "already written" + << std::endl; + return result; + } + result = SerializeAdapter::deSerialize(¶ms.seqCount, &startAddressPtr, &remainingSize, + SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + sif::warning + << "PlocSupervisorHandler::extractUpdateCommand: Failed to deserialize start sequence count" + << std::endl; + return result; + } return RETURN_OK; } diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index ebd059f9..7f0b2574 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -367,8 +367,15 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t prepareSetShutdownTimeoutCmd(const uint8_t* commandData); - ReturnValue_t extractUpdateCommand(const uint8_t* commandData, size_t size, std::string* file, - uint8_t* memoryId, uint32_t* startAddress); + struct UpdateParams { + std::string file; + uint8_t memId; + uint32_t startAddr; + uint32_t bytesWritten; + uint16_t seqCount; + }; + + ReturnValue_t extractUpdateCommand(const uint8_t* commandData, size_t size, UpdateParams& params); ReturnValue_t eventSubscription(); ReturnValue_t handleExecutionSuccessReport(const uint8_t* data); diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index c5876793..c2a46c68 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -99,8 +99,14 @@ ReturnValue_t PlocSupvHelper::setComIF(UartComIF* uartComIF_) { void PlocSupvHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; } -ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId, uint32_t startAddress, - size_t startBytesWritten, uint16_t initSeqCount) { +ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId, + uint32_t startAddress) { + return performUpdate(file, memoryId, startAddress, 0, 1); +} + +ReturnValue_t PlocSupvHelper::performUpdate(std::string file, uint8_t memoryId, + uint32_t startAddress, size_t startBytesWritten, + uint16_t initSeqCount) { ReturnValue_t result = RETURN_OK; #ifdef XIPHOS_Q7S result = FilesystemHelper::checkPath(file); @@ -127,7 +133,6 @@ ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId, ui update.memoryId = memoryId; update.startAddress = startAddress; update.progressPercent = 0; - update.remainingSize = update.length; update.bytesWritten = startBytesWritten; update.packetNum = 1; update.sequenceCount = initSeqCount; @@ -214,16 +219,19 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { std::ifstream file(update.file, std::ifstream::binary); uint16_t dataLength = 0; ccsds::SequenceFlags seqFlags; - while (update.remainingSize > 0) { + while (update.bytesWritten < update.length) { if (terminate) { terminate = false; triggerEvent(TERMINATED_UPDATE_PROCEDURE); return PROCESS_TERMINATED; } - if (update.remainingSize > supv::WriteMemory::CHUNK_MAX) { + size_t remainingSize = update.length - update.bytesWritten; + bool lastSegment = false; + if (remainingSize > supv::WriteMemory::CHUNK_MAX) { dataLength = supv::WriteMemory::CHUNK_MAX; } else { - dataLength = static_cast(update.remainingSize); + lastSegment = true; + dataLength = static_cast(remainingSize); } if (file.is_open()) { file.seekg(update.bytesWritten, std::ios::beg); @@ -239,26 +247,14 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { } if (update.bytesWritten == 0) { seqFlags = ccsds::SequenceFlags::FIRST_SEGMENT; - } else if (update.remainingSize == 0) { + } else if (lastSegment) { seqFlags = ccsds::SequenceFlags::LAST_SEGMENT; } else { seqFlags = ccsds::SequenceFlags::CONTINUATION; } resetSpParams(); - supv::WriteMemory packet(spParams); - result = packet.buildPacket(seqFlags, update.sequenceCount, update.memoryId, - update.startAddress + update.bytesWritten, dataLength, tempData); - if (result != RETURN_OK) { - triggerEvent(WRITE_MEMORY_FAILED, update.packetNum); - return result; - } - result = handlePacketTransmission(packet); - if (result != RETURN_OK) { - triggerEvent(WRITE_MEMORY_FAILED, update.packetNum); - return result; - } - uint8_t progPercent = - static_cast(std::floor(static_cast(update.bytesWritten) / update.length)); + float progress = static_cast(update.bytesWritten) / update.length; + uint8_t progPercent = std::floor(progress * 100); if (progPercent > update.progressPercent) { update.progressPercent = progPercent; if (progPercent % 5 == 0) { @@ -266,8 +262,19 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { triggerEvent(SUPV_UPDATE_PROGRESS, update.bytesWritten, update.sequenceCount); } } + supv::WriteMemory packet(spParams); + result = packet.buildPacket(seqFlags, update.sequenceCount, update.memoryId, + update.startAddress + update.bytesWritten, dataLength, tempData); + if (result != RETURN_OK) { + triggerEvent(WRITE_MEMORY_FAILED, update.bytesWritten, update.sequenceCount); + return result; + } + result = handlePacketTransmission(packet); + if (result != RETURN_OK) { + triggerEvent(WRITE_MEMORY_FAILED, update.bytesWritten, update.sequenceCount); + return result; + } update.sequenceCount++; - update.remainingSize -= dataLength; update.packetNum += 1; update.bytesWritten += dataLength; diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 0e53a9b6..d3bfc49c 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -83,8 +83,8 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha //! P1: Return value //! P2: Apid of command for which the reception of the execution report failed static const Event EXE_RECEPTION_FAILURE = MAKE_EVENT(18, severity::LOW); - //! [EXPORT] : [COMMENT] Update procedure failed when sending packet with number P1 - //! P1: Packet number for which the memory write command fails + //! [EXPORT] : [COMMENT] Update procedure failed when sending packet. + //! P1: Bytes written, P2: Sequence Count static const Event WRITE_MEMORY_FAILED = MAKE_EVENT(19, severity::LOW); static const Event SUPV_REPLY_SIZE_MISSMATCH = MAKE_EVENT(20, severity::LOW); static const Event SUPV_REPLY_CRC_MISSMATCH = MAKE_EVENT(21, severity::LOW); @@ -111,8 +111,9 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha * * @return RETURN_OK if successful, otherwise error return value */ - ReturnValue_t startUpdate(std::string file, uint8_t memoryId, uint32_t startAddress, - size_t startBytesWritten = 0, uint16_t initSeqCount = 1); + ReturnValue_t performUpdate(std::string file, uint8_t memoryId, uint32_t startAddress, + size_t startBytesWritten, uint16_t initSeqCount); + ReturnValue_t startUpdate(std::string file, uint8_t memoryId, uint32_t startAddress); /** * @brief This initiate the continuation of a failed update. @@ -158,7 +159,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha // Size of update uint32_t length; uint32_t crc; - size_t remainingSize; + // size_t remainingSize; size_t bytesWritten; uint32_t packetNum; uint16_t sequenceCount; From b503836a3d8d12d282cf2a6248fb715c0393aee6 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sun, 21 Aug 2022 01:38:45 +0200 Subject: [PATCH 37/58] hopefully last bugfix --- .../PlocSupervisorDefinitions.h | 21 +++------ linux/devices/ploc/PlocSupvHelper.cpp | 43 ++++++++++++------- mission/devices/devicedefinitions/SpBase.h | 5 +-- tmtc | 2 +- 4 files changed, 36 insertions(+), 35 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index de05c9e9..9c848160 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -1829,20 +1829,13 @@ class UpdateStatusReport : public ploc::SpTmReader { return result; } const uint8_t* dataFieldPtr = getFullData() + ccsds::HEADER_LEN; - size_t size = sizeof(memoryId); - SerializeAdapter::deSerialize(&memoryId, dataFieldPtr, &size, SerializeIF::Endianness::BIG); - dataFieldPtr += size; - size = sizeof(n); - SerializeAdapter::deSerialize(&n, dataFieldPtr, &size, SerializeIF::Endianness::BIG); - dataFieldPtr += size; - size = sizeof(startAddress); - SerializeAdapter::deSerialize(&startAddress, dataFieldPtr, &size, SerializeIF::Endianness::BIG); - dataFieldPtr += size; - size = sizeof(length); - SerializeAdapter::deSerialize(&length, dataFieldPtr, &size, SerializeIF::Endianness::BIG); - dataFieldPtr += size; - size = sizeof(crc); - SerializeAdapter::deSerialize(&crc, dataFieldPtr, &size, SerializeIF::Endianness::BIG); + 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 HasReturnvaluesIF::RETURN_OK; } diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index c2a46c68..13185d2d 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -555,32 +555,43 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { if (result != RETURN_OK) { return result; } - supv::UpdateStatusReport updateStatusReport(tmBuf.data(), tmBuf.size()); - result = handleTmReception(static_cast(updateStatusReport.getNominalSize()), - supv::recv_timeout::UPDATE_STATUS_REPORT); - result = updateStatusReport.checkCrc(); - if (result != RETURN_OK) { - sif::warning << "PlocSupvHelper::handleTmReception: CRC check failed" << std::endl; - return result; - } - if (result != RETURN_OK) { - sif::warning - << "PlocSupvHelper::handleCheckMemoryCommand: Failed to receive update status report" - << std::endl; - return result; + + // Will hold status report for later processing + std::array statusReportBuf{}; + { + supv::UpdateStatusReport updateStatusReport(tmBuf.data(), tmBuf.size()); + result = handleTmReception(static_cast(updateStatusReport.getNominalSize()), + supv::recv_timeout::UPDATE_STATUS_REPORT); + if (result != RETURN_OK) { + sif::warning + << "PlocSupvHelper::handleCheckMemoryCommand: Failed to receive update status report" + << std::endl; + return result; + } + result = updateStatusReport.checkCrc(); + if (result != RETURN_OK) { + sif::warning << "PlocSupvHelper::handleTmReception: CRC check failed" << std::endl; + return result; + } + // We need to copy this into another buffer. Otherwise, it will be overwritten + // when reading the execution report. + std::memcpy(statusReportBuf.data(), tmBuf.data(), updateStatusReport.getNominalSize()); } + result = handleExe(CRC_EXECUTION_TIMEOUT); if (result != RETURN_OK) { return result; } - result = updateStatusReport.parseDataField(); + // Now process the status report + supv::UpdateStatusReport statusReportCopy(statusReportBuf.data(), statusReportBuf.size()); + result = statusReportCopy.parseDataField(); if (result != RETURN_OK) { return result; } - result = updateStatusReport.verifycrc(update.crc); + result = statusReportCopy.verifycrc(update.crc); if (result != RETURN_OK) { sif::warning << "PlocSupvHelper::handleCheckMemoryCommand: CRC failure. Expected CRC 0x" - << std::hex << update.crc << " but received CRC 0x" << updateStatusReport.getCrc() + << std::hex << update.crc << " but received CRC 0x" << statusReportCopy.getCrc() << std::endl; return result; } diff --git a/mission/devices/devicedefinitions/SpBase.h b/mission/devices/devicedefinitions/SpBase.h index 82a3c0c7..ef1f70b8 100644 --- a/mission/devices/devicedefinitions/SpBase.h +++ b/mission/devices/devicedefinitions/SpBase.h @@ -107,10 +107,7 @@ class SpTmReader : public SpacePacketReader { uint16_t getPayloadDataLength() { return getPacketDataLen() - 2; } ReturnValue_t checkCrc() { - const uint8_t* crcPtr = getFullData() + getFullPacketLen() - CRC_SIZE; - uint16_t receivedCrc = *(crcPtr) << 8 | *(crcPtr + 1); - uint16_t recalculatedCrc = CRC::crc16ccitt(getFullData(), getFullPacketLen() - CRC_SIZE); - if (recalculatedCrc != receivedCrc) { + if (CRC::crc16ccitt(getFullData(), getFullPacketLen()) != 0) { return HasReturnvaluesIF::RETURN_FAILED; } return HasReturnvaluesIF::RETURN_OK; diff --git a/tmtc b/tmtc index 00e99292..9ed2593a 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 00e99292cc158a347f485507537fa5b63262243b +Subproject commit 9ed2593a54fecbea89dd812bbe87d4122a30bf83 From 1f3365960ddfd6afd6d6bdff1f8a11bfcab84c97 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Sun, 21 Aug 2022 08:38:21 +0200 Subject: [PATCH 38/58] re-run generators --- generators/bsp_q7s_events.csv | 3 +- generators/bsp_q7s_returnvalues.csv | 634 +++++++++--------- generators/events/translateEvents.cpp | 7 +- generators/objects/translateObjects.cpp | 2 +- linux/fsfwconfig/events/translateEvents.cpp | 7 +- linux/fsfwconfig/objects/translateObjects.cpp | 2 +- tmtc | 2 +- 7 files changed, 332 insertions(+), 325 deletions(-) diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index d4258cb6..0aa188c2 100644 --- a/generators/bsp_q7s_events.csv +++ b/generators/bsp_q7s_events.csv @@ -205,9 +205,10 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 13616;0x3530;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 13617;0x3531;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 13618;0x3532;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 -13619;0x3533;WRITE_MEMORY_FAILED;LOW;Update procedure failed when sending packet with number P1 P1: Packet number for which the memory write command fails;linux/devices/ploc/PlocSupvHelper.h +13619;0x3533;WRITE_MEMORY_FAILED;LOW;Update procedure failed when sending packet. P1: Bytes written, P2: Sequence Count;linux/devices/ploc/PlocSupvHelper.h 13620;0x3534;SUPV_REPLY_SIZE_MISSMATCH;LOW;;linux/devices/ploc/PlocSupvHelper.h 13621;0x3535;SUPV_REPLY_CRC_MISSMATCH;LOW;;linux/devices/ploc/PlocSupvHelper.h +13622;0x3536;SUPV_UPDATE_PROGRESS;INFO;Will be triggered every 5 percent of the update progress. P1: Bytes written, P2: Sequence Count;linux/devices/ploc/PlocSupvHelper.h 13700;0x3584;ALLOC_FAILURE;MEDIUM;;bsp_q7s/core/CoreController.h 13701;0x3585;REBOOT_SW;MEDIUM; Software reboot occurred. Can also be a systemd reboot. P1: Current Chip, P2: Current Copy;bsp_q7s/core/CoreController.h 13702;0x3586;REBOOT_MECHANISM_TRIGGERED;MEDIUM;The reboot mechanism was triggered. P1: First 16 bits: Last Chip, Last 16 bits: Last Copy, P2: Each byte is the respective reboot count for the slots;bsp_q7s/core/CoreController.h diff --git a/generators/bsp_q7s_returnvalues.csv b/generators/bsp_q7s_returnvalues.csv index ab196298..1c99ffdc 100644 --- a/generators/bsp_q7s_returnvalues.csv +++ b/generators/bsp_q7s_returnvalues.csv @@ -1,14 +1,13 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x0000;OK;System-wide code for ok.;0;HasReturnvaluesIF;fsfw/returnvalues/HasReturnvaluesIF.h 0x0001;Failed;Unspecified system-wide code for failed.;1;HasReturnvaluesIF;fsfw/returnvalues/HasReturnvaluesIF.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 +0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CCSDSHandler.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 @@ -21,12 +20,13 @@ 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 @@ -44,126 +44,129 @@ 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/CCSDSHandler.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/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 -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 -0x4300;FILS_GenericFileError;;0;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4301;FILS_IsBusy;;1;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4302;FILS_InvalidParameters;;2;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4305;FILS_FileDoesNotExist;;5;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4306;FILS_FileAlreadyExists;;6;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4307;FILS_FileLocked;;7;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x430a;FILS_DirectoryDoesNotExist;;10;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x430b;FILS_DirectoryAlreadyExists;;11;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x430c;FILS_DirectoryNotEmpty;;12;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x430f;FILS_SequencePacketMissingWrite;;15;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4310;FILS_SequencePacketMissingRead;;16;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.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 -0x1101;AL_Full;;1;ARRAY_LIST;fsfw/src/fsfw/container/ArrayList.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 -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/TcDistributor.h +0x1c02;TCD_DestinationNotFound;;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h +0x1c03;TCD_ServiceIdAlreadyExists;;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h +0x1b00;TCC_InvalidCcsdsVersion;;0;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b01;TCC_InvalidApid;;1;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b02;TCC_InvalidPacketType;;2;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b03;TCC_InvalidSecHeaderField;;3;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b04;TCC_IncorrectPrimaryHeader;;4;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b05;TCC_IncompletePacket;;5;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b06;TCC_InvalidPusVersion;;6;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b07;TCC_IncorrectChecksum;;7;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b08;TCC_IllegalPacketSubtype;;8;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b09;TCC_IncorrectSecondaryHeader;;9;PACKET_CHECK;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 @@ -204,9 +207,93 @@ 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_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_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_InvalidDirectiveFields;;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_FinishedCantParseFsResponses;;6;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 +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 @@ -215,19 +302,39 @@ 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/TcDistributor.h -0x1c02;TCD_DestinationNotFound;;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h -0x1c03;TCD_ServiceIdAlreadyExists;;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h -0x1b00;TCC_InvalidCcsdsVersion;;0;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b01;TCC_InvalidApid;;1;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b02;TCC_InvalidPacketType;;2;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b03;TCC_InvalidSecHeaderField;;3;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b04;TCC_IncorrectPrimaryHeader;;4;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b05;TCC_IncompletePacket;;5;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b06;TCC_InvalidPusVersion;;6;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b07;TCC_IncorrectChecksum;;7;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b08;TCC_IllegalPacketSubtype;;8;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b09;TCC_IncorrectSecondaryHeader;;9;PACKET_CHECK;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 +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 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 @@ -235,76 +342,6 @@ 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 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 @@ -323,52 +360,44 @@ 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_InvalidDirectiveFields;;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_FinishedCantParseFsResponses;;6;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 -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_TimeshiftingNotPossible;;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4203;PUS11_InvalidRelativeTime;;3;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 +0x4300;FILS_GenericFileError;;0;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4301;FILS_IsBusy;;1;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4302;FILS_InvalidParameters;;2;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4305;FILS_FileDoesNotExist;;5;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4306;FILS_FileAlreadyExists;;6;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4307;FILS_FileLocked;;7;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x430a;FILS_DirectoryDoesNotExist;;10;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x430b;FILS_DirectoryAlreadyExists;;11;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x430c;FILS_DirectoryNotEmpty;;12;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x430f;FILS_SequencePacketMissingWrite;;15;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4310;FILS_SequencePacketMissingRead;;16;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.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 @@ -378,12 +407,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 @@ -405,58 +434,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_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 -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/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 0x64a0;FSHLP_SdNotMounted;SD card specified with path string not mounted;160;FILE_SYSTEM_HELPER;bsp_q7s/memory/FilesystemHelper.h 0x64a1;FSHLP_FileNotExists;Specified file does not exist on filesystem;161;FILE_SYSTEM_HELPER;bsp_q7s/memory/FilesystemHelper.h 0x6a00;SDMA_OpOngoing;;0;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h @@ -469,3 +468,4 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x6a0d;SDMA_UnmountError;;13;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h 0x6a0e;SDMA_SystemCallError;;14;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h 0x6a0f;SDMA_PopenCallError;;15;SD_CARD_MANAGER;bsp_q7s/memory/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 18826deb..debb17d5 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 213 translations. + * @brief Auto-generated event translation file. Contains 214 translations. * @details - * Generated on: 2022-08-18 11:23:13 + * Generated on: 2022-08-21 08:37:22 */ #include "translateEvents.h" @@ -210,6 +210,7 @@ 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 *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; const char *REBOOT_SW_STRING = "REBOOT_SW"; const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED"; @@ -627,6 +628,8 @@ const char *translateEvents(Event event) { return SUPV_REPLY_SIZE_MISSMATCH_STRING; case (13621): return SUPV_REPLY_CRC_MISSMATCH_STRING; + case (13622): + return SUPV_UPDATE_PROGRESS_STRING; case (13700): return ALLOC_FAILURE_STRING; case (13701): diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index a052ec02..2f561520 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 133 translations. - * Generated on: 2022-08-18 11:23:13 + * Generated on: 2022-08-21 08:37:22 */ #include "translateObjects.h" diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index 18826deb..debb17d5 100644 --- a/linux/fsfwconfig/events/translateEvents.cpp +++ b/linux/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 213 translations. + * @brief Auto-generated event translation file. Contains 214 translations. * @details - * Generated on: 2022-08-18 11:23:13 + * Generated on: 2022-08-21 08:37:22 */ #include "translateEvents.h" @@ -210,6 +210,7 @@ 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 *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; const char *REBOOT_SW_STRING = "REBOOT_SW"; const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED"; @@ -627,6 +628,8 @@ const char *translateEvents(Event event) { return SUPV_REPLY_SIZE_MISSMATCH_STRING; case (13621): return SUPV_REPLY_CRC_MISSMATCH_STRING; + case (13622): + return SUPV_UPDATE_PROGRESS_STRING; case (13700): return ALLOC_FAILURE_STRING; case (13701): diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index a052ec02..2f561520 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 133 translations. - * Generated on: 2022-08-18 11:23:13 + * Generated on: 2022-08-21 08:37:22 */ #include "translateObjects.h" diff --git a/tmtc b/tmtc index 9ed2593a..57dbef74 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 9ed2593a54fecbea89dd812bbe87d4122a30bf83 +Subproject commit 57dbef741b225a023353d8dbf814727ba8b44895 From f98411f421236abdd309e98e75a8eca671e47936 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 22 Aug 2022 10:35:23 +0200 Subject: [PATCH 39/58] speed up crc proc significantly --- linux/devices/ploc/PlocSupvHelper.cpp | 22 +++++++++++++++------- 1 file changed, 15 insertions(+), 7 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 13185d2d..a8858e25 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -1,5 +1,7 @@ #include "PlocSupvHelper.h" +#include + #include #include #include @@ -10,7 +12,6 @@ #include "bsp_q7s/memory/SdCardManager.h" #endif -#include "fsfw/globalfunctions/CRC.h" #include "fsfw/tasks/TaskFactory.h" #include "fsfw/timemanager/Countdown.h" #include "mission/utility/Filenaming.h" @@ -509,32 +510,39 @@ ReturnValue_t PlocSupvHelper::calcImageCrc() { #ifdef XIPHOS_Q7S result = FilesystemHelper::checkPath(update.file); #endif + auto crc16Calcer = etl::crc16_ccitt(); if (result != RETURN_OK) { sif::warning << "PlocSupvHelper::calcImageCrc: File " << update.file << " does not exist" << std::endl; return result; } std::ifstream file(update.file, std::ifstream::binary); - uint16_t remainder = CRC16_INIT; - uint8_t input; + std::array crcBuf; #if OBSW_DEBUG_PLOC_SUPERVISOR == 1 ProgressPrinter progress("Supervisor update crc calculation", update.length, ProgressPrinter::ONE_PERCENT); #endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ uint32_t byteCount = 0; - for (byteCount = 0; byteCount < update.length; byteCount++) { + while (byteCount < update.length) { + size_t bytesToRead = 1024; + size_t remLen = update.length - byteCount; + if (remLen < 1024) { + bytesToRead = remLen; + } file.seekg(byteCount, file.beg); - file.read(reinterpret_cast(&input), 1); - remainder = CRC::crc16ccitt(&input, sizeof(input), remainder); + file.read(reinterpret_cast(crcBuf.data()), bytesToRead); + crc16Calcer.add(crcBuf.begin(), crcBuf.begin() + bytesToRead); + #if OBSW_DEBUG_PLOC_SUPERVISOR == 1 progress.print(byteCount); #endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ + byteCount += bytesToRead; } #if OBSW_DEBUG_PLOC_SUPERVISOR == 1 progress.print(byteCount); #endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ file.close(); - update.crc = remainder; + update.crc = crc16Calcer.value(); return result; } From e71e2e7879e000fd9e4f75423db7009938bdb138 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 22 Aug 2022 12:08:39 +0200 Subject: [PATCH 40/58] new command to only perform mem check --- .../PlocSupervisorDefinitions.h | 5 +- linux/devices/ploc/PlocSupervisorHandler.cpp | 24 +++++ linux/devices/ploc/PlocSupvHelper.cpp | 89 ++++++++++++------- linux/devices/ploc/PlocSupvHelper.h | 15 +++- tmtc | 2 +- 5 files changed, 96 insertions(+), 39 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 9c848160..348fed54 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -60,6 +60,7 @@ static const DeviceCommandId_t REQUEST_ADC_REPORT = 57; 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 = 61; /** Reply IDs */ static const DeviceCommandId_t ACK_REPORT = 100; @@ -267,8 +268,8 @@ 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; +static const uint32_t ERASE_MEMORY_TIMEOUT = 60000; +static const uint32_t UPDATE_STATUS_REPORT_TIMEOUT = 70000; } // namespace recv_timeout /** diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 1ad77883..7bc78f61 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -132,6 +132,30 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, plocSupvHelperExecuting = true; return EXECUTION_FINISHED; } + case MEMORY_CHECK: { + size_t deserLen = 9; + uint8_t memId; + uint32_t startAddr; + uint32_t sizeToCheck; + result = + SerializeAdapter::deSerialize(&memId, &data, &deserLen, SerializeIF::Endianness::NETWORK); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::deSerialize(&startAddr, &data, &deserLen, + SerializeIF::Endianness::NETWORK); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + result = SerializeAdapter::deSerialize(&sizeToCheck, &data, &deserLen, + SerializeIF::Endianness::NETWORK); + if (result != HasReturnvaluesIF::RETURN_OK) { + return result; + } + supvHelper->performMemCheck(memId, startAddr, sizeToCheck); + plocSupvHelperExecuting = true; + return EXECUTION_FINISHED; + } case LOGGING_REQUEST_EVENT_BUFFERS: { if (size > config::MAX_PATH_SIZE) { return SupvReturnValuesIF::FILENAME_TOO_LONG; diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index a8858e25..f07acaef 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -57,6 +57,13 @@ ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { internalState = InternalState::IDLE; break; } + case InternalState::CHECK_MEMORY: { + sif::info << "PlocSupvHelper::performUpdate: Memory Check" << std::endl; + result = handleCheckMemoryCommand(); + triggerEvent(SUPV_MEM_CHECK_STATUS, result); + internalState = InternalState::IDLE; + break; + } case InternalState::CONTINUE_UPDATE: { result = continueUpdate(); if (result == RETURN_OK) { @@ -143,6 +150,17 @@ ReturnValue_t PlocSupvHelper::performUpdate(std::string file, uint8_t memoryId, return result; } +ReturnValue_t PlocSupvHelper::performMemCheck(uint8_t memoryId, uint32_t startAddress, + size_t sizeToCheck) { + update.memoryId = memoryId; + update.startAddress = startAddress; + update.length = sizeToCheck; + internalState = InternalState::CHECK_MEMORY; + uartComIF->flushUartTxAndRxBuf(comCookie); + semaphore.release(); + return HasReturnvaluesIF::RETURN_OK; +} + void PlocSupvHelper::initiateUpdateContinuation() { internalState = InternalState::CONTINUE_UPDATE; semaphore.release(); @@ -260,19 +278,22 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { update.progressPercent = progPercent; if (progPercent % 5 == 0) { // Useful to allow restarting the update - triggerEvent(SUPV_UPDATE_PROGRESS, update.bytesWritten, update.sequenceCount); + triggerEvent(SUPV_UPDATE_PROGRESS, buildProgParams1(progPercent, update.sequenceCount), + update.bytesWritten); } } supv::WriteMemory packet(spParams); result = packet.buildPacket(seqFlags, update.sequenceCount, update.memoryId, update.startAddress + update.bytesWritten, dataLength, tempData); if (result != RETURN_OK) { - triggerEvent(WRITE_MEMORY_FAILED, update.bytesWritten, update.sequenceCount); + triggerEvent(WRITE_MEMORY_FAILED, buildProgParams1(progPercent, update.sequenceCount), + update.bytesWritten); return result; } result = handlePacketTransmission(packet); if (result != RETURN_OK) { - triggerEvent(WRITE_MEMORY_FAILED, update.bytesWritten, update.sequenceCount); + triggerEvent(WRITE_MEMORY_FAILED, buildProgParams1(progPercent, update.sequenceCount), + update.bytesWritten); return result; } update.sequenceCount++; @@ -286,6 +307,10 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { return result; } +uint32_t PlocSupvHelper::buildProgParams1(uint8_t percent, uint16_t seqCount) { + return (static_cast(percent) << 24) | static_cast(seqCount); +} + ReturnValue_t PlocSupvHelper::performEventBufferRequest() { using namespace supv; ReturnValue_t result = RETURN_OK; @@ -352,7 +377,7 @@ ReturnValue_t PlocSupvHelper::eraseMemory() { if (result != RETURN_OK) { return result; } - result = handlePacketTransmission(eraseMemory, supv::recv_timeout::ERASE_MEMORY); + result = handlePacketTransmission(eraseMemory, supv::recv_timeout::ERASE_MEMORY_TIMEOUT); if (result != RETURN_OK) { return result; } @@ -419,7 +444,7 @@ ReturnValue_t PlocSupvHelper::handleAck() { ReturnValue_t PlocSupvHelper::handleExe(uint32_t timeout) { ReturnValue_t result = RETURN_OK; - result = handleTmReception(supv::SIZE_EXE_REPORT, timeout); + result = handleTmReception(supv::SIZE_EXE_REPORT, tmBuf.data(), timeout); if (result != RETURN_OK) { triggerEvent(EXE_RECEPTION_FAILURE, result, static_cast(rememberApid)); sif::warning << "PlocSupvHelper::handleExe: Error in reception of execution report" @@ -443,13 +468,17 @@ ReturnValue_t PlocSupvHelper::handleExe(uint32_t timeout) { return RETURN_OK; } -ReturnValue_t PlocSupvHelper::handleTmReception(size_t remainingBytes, uint32_t timeout) { +ReturnValue_t PlocSupvHelper::handleTmReception(size_t remainingBytes, uint8_t* readBuf, + uint32_t timeout) { ReturnValue_t result = RETURN_OK; size_t readBytes = 0; size_t currentBytes = 0; Countdown countdown(timeout); + if (readBuf == nullptr) { + readBuf = tmBuf.data(); + } while (!countdown.hasTimedOut()) { - result = receive(tmBuf.data() + readBytes, ¤tBytes, remainingBytes); + result = receive(readBuf + readBytes, ¤tBytes, remainingBytes); if (result != RETURN_OK) { return result; } @@ -461,7 +490,7 @@ ReturnValue_t PlocSupvHelper::handleTmReception(size_t remainingBytes, uint32_t } if (remainingBytes != 0) { sif::warning << "PlocSupvHelper::handleTmReception: Failed to read " << std::dec - << remainingBytes << " bytes" << std::endl; + << remainingBytes << " remaining bytes" << std::endl; return RETURN_FAILED; } return result; @@ -549,6 +578,9 @@ ReturnValue_t PlocSupvHelper::calcImageCrc() { ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { ReturnValue_t result = RETURN_OK; resetSpParams(); + // Will hold status report for later processing + std::array statusReportBuf{}; + supv::UpdateStatusReport updateStatusReport(statusReportBuf.data(), statusReportBuf.size()); // Verification of update write procedure supv::CheckMemory packet(spParams); result = packet.buildPacket(update.memoryId, update.startAddress, update.length); @@ -564,42 +596,35 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { return result; } - // Will hold status report for later processing - std::array statusReportBuf{}; - { - supv::UpdateStatusReport updateStatusReport(tmBuf.data(), tmBuf.size()); - result = handleTmReception(static_cast(updateStatusReport.getNominalSize()), - supv::recv_timeout::UPDATE_STATUS_REPORT); - if (result != RETURN_OK) { - sif::warning - << "PlocSupvHelper::handleCheckMemoryCommand: Failed to receive update status report" - << std::endl; - return result; - } - result = updateStatusReport.checkCrc(); - if (result != RETURN_OK) { - sif::warning << "PlocSupvHelper::handleTmReception: CRC check failed" << std::endl; - return result; - } - // We need to copy this into another buffer. Otherwise, it will be overwritten - // when reading the execution report. - std::memcpy(statusReportBuf.data(), tmBuf.data(), updateStatusReport.getNominalSize()); + result = + handleTmReception(static_cast(updateStatusReport.getNominalSize()), + statusReportBuf.data(), supv::recv_timeout::UPDATE_STATUS_REPORT_TIMEOUT); + if (result != RETURN_OK) { + sif::warning + << "PlocSupvHelper::handleCheckMemoryCommand: Failed to receive update status report" + << std::endl; + return result; + } + result = updateStatusReport.checkCrc(); + if (result != RETURN_OK) { + sif::warning << "PlocSupvHelper::handleTmReception: CRC check failed" << std::endl; + return result; } result = handleExe(CRC_EXECUTION_TIMEOUT); if (result != RETURN_OK) { return result; } + // Now process the status report - supv::UpdateStatusReport statusReportCopy(statusReportBuf.data(), statusReportBuf.size()); - result = statusReportCopy.parseDataField(); + result = updateStatusReport.parseDataField(); if (result != RETURN_OK) { return result; } - result = statusReportCopy.verifycrc(update.crc); + result = updateStatusReport.verifycrc(update.crc); if (result != RETURN_OK) { sif::warning << "PlocSupvHelper::handleCheckMemoryCommand: CRC failure. Expected CRC 0x" - << std::hex << update.crc << " but received CRC 0x" << statusReportCopy.getCrc() + << std::hex << update.crc << " but received CRC 0x" << updateStatusReport.getCrc() << std::endl; return result; } diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index d3bfc49c..ee745b54 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -84,14 +84,17 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha //! P2: Apid of command for which the reception of the execution report failed static const Event EXE_RECEPTION_FAILURE = MAKE_EVENT(18, severity::LOW); //! [EXPORT] : [COMMENT] Update procedure failed when sending packet. - //! P1: Bytes written, P2: Sequence Count + //! P1: First byte percent, Third and Fourht bytes Sequence Count, P2: Bytes written static const Event WRITE_MEMORY_FAILED = MAKE_EVENT(19, severity::LOW); static const Event SUPV_REPLY_SIZE_MISSMATCH = MAKE_EVENT(20, severity::LOW); static const Event SUPV_REPLY_CRC_MISSMATCH = MAKE_EVENT(21, severity::LOW); //! [EXPORT] : [COMMENT] Will be triggered every 5 percent of the update progress. - //! P1: Bytes written, P2: Sequence Count + //! P1: First byte percent, Third and Fourht bytes Sequence Count, P2: Bytes written static constexpr Event SUPV_UPDATE_PROGRESS = MAKE_EVENT(22, severity::INFO); + //! Status of memory check command + //! P1: Returncode, 0 for success, other value with returncode for failure + static constexpr Event SUPV_MEM_CHECK_STATUS = MAKE_EVENT(23, severity::INFO); PlocSupvHelper(object_id_t objectId); virtual ~PlocSupvHelper(); @@ -115,6 +118,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha size_t startBytesWritten, uint16_t initSeqCount); ReturnValue_t startUpdate(std::string file, uint8_t memoryId, uint32_t startAddress); + ReturnValue_t performMemCheck(uint8_t memoryId, uint32_t startAddress, size_t sizeToCheck); /** * @brief This initiate the continuation of a failed update. */ @@ -130,6 +134,8 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha */ void stopProcess(); + static uint32_t buildProgParams1(uint8_t percent, uint16_t seqCount); + private: static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_SUPV_HELPER; @@ -177,7 +183,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha EventBufferRequest eventBufferReq; - enum class InternalState { IDLE, UPDATE, CONTINUE_UPDATE, REQUEST_EVENT_BUFFER }; + enum class InternalState { IDLE, UPDATE, CONTINUE_UPDATE, REQUEST_EVENT_BUFFER, CHECK_MEMORY }; InternalState internalState = InternalState::IDLE; @@ -233,7 +239,8 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha * @note It can take up to 70 seconds until the supervisor replies with an acknowledgment * failure report. */ - ReturnValue_t handleTmReception(size_t remainingBytes, uint32_t timeout = 70000); + ReturnValue_t handleTmReception(size_t remainingBytes, uint8_t* readBuf = nullptr, + uint32_t timeout = 70000); ReturnValue_t checkReceivedTm(ploc::SpTmReader& reader); ReturnValue_t selectMemory(); diff --git a/tmtc b/tmtc index 57dbef74..b3f0c08b 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 57dbef741b225a023353d8dbf814727ba8b44895 +Subproject commit b3f0c08bd757c8b6616398eb6dbd64c9107d59bc From b3bb029c47e13f0e6bb500e7e3590f880e735524 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 22 Aug 2022 12:41:08 +0200 Subject: [PATCH 41/58] something wrong with mem check --- generators/bsp_q7s_events.csv | 5 +- generators/events/translateEvents.cpp | 7 ++- generators/objects/translateObjects.cpp | 2 +- .../PlocSupervisorDefinitions.h | 4 +- linux/devices/ploc/PlocSupvHelper.cpp | 47 +++++++++++++------ linux/devices/ploc/PlocSupvHelper.h | 1 + linux/fsfwconfig/events/translateEvents.cpp | 7 ++- linux/fsfwconfig/objects/translateObjects.cpp | 2 +- tmtc | 2 +- 9 files changed, 51 insertions(+), 26 deletions(-) diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index 0aa188c2..7d822e1d 100644 --- a/generators/bsp_q7s_events.csv +++ b/generators/bsp_q7s_events.csv @@ -205,10 +205,11 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 13616;0x3530;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 13617;0x3531;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 13618;0x3532;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 -13619;0x3533;WRITE_MEMORY_FAILED;LOW;Update procedure failed when sending packet. P1: Bytes written, P2: Sequence Count;linux/devices/ploc/PlocSupvHelper.h +13619;0x3533;WRITE_MEMORY_FAILED;LOW;Update procedure failed when sending packet. P1: First byte percent, Third and Fourht bytes Sequence Count, P2: Bytes written;linux/devices/ploc/PlocSupvHelper.h 13620;0x3534;SUPV_REPLY_SIZE_MISSMATCH;LOW;;linux/devices/ploc/PlocSupvHelper.h 13621;0x3535;SUPV_REPLY_CRC_MISSMATCH;LOW;;linux/devices/ploc/PlocSupvHelper.h -13622;0x3536;SUPV_UPDATE_PROGRESS;INFO;Will be triggered every 5 percent of the update progress. P1: Bytes written, P2: Sequence Count;linux/devices/ploc/PlocSupvHelper.h +13622;0x3536;SUPV_UPDATE_PROGRESS;INFO;Will be triggered every 5 percent of the update progress. P1: First byte percent, Third and Fourht bytes Sequence Count, P2: Bytes written;linux/devices/ploc/PlocSupvHelper.h +13623;0x3537;SUPV_MEM_CHECK_STATUS;INFO;;linux/devices/ploc/PlocSupvHelper.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 debb17d5..f9511036 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 214 translations. + * @brief Auto-generated event translation file. Contains 215 translations. * @details - * Generated on: 2022-08-21 08:37:22 + * Generated on: 2022-08-22 12:35:41 */ #include "translateEvents.h" @@ -211,6 +211,7 @@ 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 *SUPV_MEM_CHECK_STATUS_STRING = "SUPV_MEM_CHECK_STATUS"; const char *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; const char *REBOOT_SW_STRING = "REBOOT_SW"; const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED"; @@ -630,6 +631,8 @@ const char *translateEvents(Event event) { return SUPV_REPLY_CRC_MISSMATCH_STRING; case (13622): return SUPV_UPDATE_PROGRESS_STRING; + case (13623): + return SUPV_MEM_CHECK_STATUS_STRING; case (13700): return ALLOC_FAILURE_STRING; case (13701): diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index 2f561520..de55983c 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 133 translations. - * Generated on: 2022-08-21 08:37:22 + * Generated on: 2022-08-22 12:35:41 */ #include "translateObjects.h" diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 348fed54..9c371305 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -268,8 +268,8 @@ 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_TIMEOUT = 60000; -static const uint32_t UPDATE_STATUS_REPORT_TIMEOUT = 70000; +static const uint32_t ERASE_MEMORY = 60000; +static const uint32_t UPDATE_STATUS_REPORT = 70000; } // namespace recv_timeout /** diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index f07acaef..b324b15b 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -377,7 +377,7 @@ ReturnValue_t PlocSupvHelper::eraseMemory() { if (result != RETURN_OK) { return result; } - result = handlePacketTransmission(eraseMemory, supv::recv_timeout::ERASE_MEMORY_TIMEOUT); + result = handlePacketTransmission(eraseMemory, supv::recv_timeout::ERASE_MEMORY); if (result != RETURN_OK) { return result; } @@ -451,8 +451,14 @@ ReturnValue_t PlocSupvHelper::handleExe(uint32_t timeout) { << std::endl; return result; } + + return exeReportHandling(); +} + +ReturnValue_t PlocSupvHelper::exeReportHandling() { supv::ExecutionReport exeReport(tmBuf.data(), tmBuf.size()); - result = checkReceivedTm(exeReport); + + ReturnValue_t result = checkReceivedTm(exeReport); if (result != RETURN_OK) { return result; } @@ -465,7 +471,7 @@ ReturnValue_t PlocSupvHelper::handleExe(uint32_t timeout) { } return result; } - return RETURN_OK; + return exeReportHandling(); } ReturnValue_t PlocSupvHelper::handleTmReception(size_t remainingBytes, uint8_t* readBuf, @@ -597,18 +603,29 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { } result = - handleTmReception(static_cast(updateStatusReport.getNominalSize()), - statusReportBuf.data(), supv::recv_timeout::UPDATE_STATUS_REPORT_TIMEOUT); - if (result != RETURN_OK) { - sif::warning - << "PlocSupvHelper::handleCheckMemoryCommand: Failed to receive update status report" - << std::endl; - return result; - } - result = updateStatusReport.checkCrc(); - if (result != RETURN_OK) { - sif::warning << "PlocSupvHelper::handleTmReception: CRC check failed" << std::endl; - return result; + handleTmReception(ccsds::HEADER_LEN, tmBuf.data(), supv::recv_timeout::UPDATE_STATUS_REPORT); + SpacePacketReader spReader(tmBuf.data(), tmBuf.size()); + if (spReader.getApid() == supv::APID_EXE_FAILURE) { + size_t remBytes = spReader.getPacketDataLen() + 1; + result = handleTmReception(remBytes, tmBuf.data() + ccsds::HEADER_LEN); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "Reading exe failure report failed" << std::endl; + } + return exeReportHandling(); + } else if (spReader.getApid() == supv::APID_UPDATE_STATUS_REPORT) { + size_t remBytes = spReader.getPacketDataLen() + 1; + result = handleTmReception(remBytes, tmBuf.data() + ccsds::HEADER_LEN); + if (result != RETURN_OK) { + sif::warning + << "PlocSupvHelper::handleCheckMemoryCommand: Failed to receive update status report" + << std::endl; + return result; + } + result = updateStatusReport.checkCrc(); + if (result != RETURN_OK) { + sif::warning << "PlocSupvHelper::handleTmReception: CRC check failed" << std::endl; + return result; + } } result = handleExe(CRC_EXECUTION_TIMEOUT); diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index ee745b54..81cbfd1d 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -250,6 +250,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha // finished. ReturnValue_t calcImageCrc(); ReturnValue_t handleCheckMemoryCommand(); + ReturnValue_t exeReportHandling(); /** * @brief Return size of file with name filename * diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index debb17d5..f9511036 100644 --- a/linux/fsfwconfig/events/translateEvents.cpp +++ b/linux/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 214 translations. + * @brief Auto-generated event translation file. Contains 215 translations. * @details - * Generated on: 2022-08-21 08:37:22 + * Generated on: 2022-08-22 12:35:41 */ #include "translateEvents.h" @@ -211,6 +211,7 @@ 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 *SUPV_MEM_CHECK_STATUS_STRING = "SUPV_MEM_CHECK_STATUS"; const char *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; const char *REBOOT_SW_STRING = "REBOOT_SW"; const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED"; @@ -630,6 +631,8 @@ const char *translateEvents(Event event) { return SUPV_REPLY_CRC_MISSMATCH_STRING; case (13622): return SUPV_UPDATE_PROGRESS_STRING; + case (13623): + return SUPV_MEM_CHECK_STATUS_STRING; case (13700): return ALLOC_FAILURE_STRING; case (13701): diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index 2f561520..de55983c 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 133 translations. - * Generated on: 2022-08-21 08:37:22 + * Generated on: 2022-08-22 12:35:41 */ #include "translateObjects.h" diff --git a/tmtc b/tmtc index b3f0c08b..425870d1 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit b3f0c08bd757c8b6616398eb6dbd64c9107d59bc +Subproject commit 425870d16150f5b99e8e450ac892104e557aff20 From 663b65f15913b50b2e7fff7ef741fac110e020ab Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 22 Aug 2022 13:50:24 +0200 Subject: [PATCH 42/58] memory check always based on file now --- .../PlocSupervisorDefinitions.h | 2 +- linux/devices/ploc/PlocSupervisorHandler.cpp | 88 +++++++++++-------- linux/devices/ploc/PlocSupervisorHandler.h | 2 + linux/devices/ploc/PlocSupvHelper.cpp | 81 +++++++++++++---- linux/devices/ploc/PlocSupvHelper.h | 11 ++- tmtc | 2 +- 6 files changed, 127 insertions(+), 59 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index 9c371305..d36e4c0c 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -60,7 +60,7 @@ static const DeviceCommandId_t REQUEST_ADC_REPORT = 57; 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 = 61; +static const DeviceCommandId_t MEMORY_CHECK_WITH_FILE = 61; /** Reply IDs */ static const DeviceCommandId_t ACK_REPORT = 100; diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 7bc78f61..1e2a20f3 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -1,5 +1,7 @@ #include "PlocSupervisorHandler.h" +#include + #include #include #include @@ -132,27 +134,16 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, plocSupvHelperExecuting = true; return EXECUTION_FINISHED; } - case MEMORY_CHECK: { - size_t deserLen = 9; - uint8_t memId; - uint32_t startAddr; - uint32_t sizeToCheck; - result = - SerializeAdapter::deSerialize(&memId, &data, &deserLen, SerializeIF::Endianness::NETWORK); + case MEMORY_CHECK_WITH_FILE: { + UpdateParams params; + ReturnValue_t result = extractBaseParams(&data, size, params); if (result != HasReturnvaluesIF::RETURN_OK) { return result; } - result = SerializeAdapter::deSerialize(&startAddr, &data, &deserLen, - SerializeIF::Endianness::NETWORK); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; + if (not std::filesystem::exists(params.file)) { + return HasFileSystemIF::FILE_DOES_NOT_EXIST; } - result = SerializeAdapter::deSerialize(&sizeToCheck, &data, &deserLen, - SerializeIF::Endianness::NETWORK); - if (result != HasReturnvaluesIF::RETURN_OK) { - return result; - } - supvHelper->performMemCheck(memId, startAddr, sizeToCheck); + supvHelper->performMemCheck(params.file, params.memId, params.startAddr); plocSupvHelperExecuting = true; return EXECUTION_FINISHED; } @@ -886,7 +877,9 @@ void PlocSupervisorHandler::handleEvent(EventMessage* eventMessage) { 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_CONTINUE_UPDATE_SUCCESSFUL || + event == PlocSupvHelper::SUPV_MEM_CHECK_FAIL || + event == PlocSupvHelper::SUPV_MEM_CHECK_OK) { result = this->executeAction(supv::SHUTDOWN_MPSOC, NO_COMMANDER, nullptr, 0); if (result != RETURN_OK) { triggerEvent(SUPV_MPSOC_SHUWDOWN_BUILD_FAILED); @@ -1998,30 +1991,15 @@ ReturnValue_t PlocSupervisorHandler::getTimeStampString(std::string& timeStamp) ReturnValue_t PlocSupervisorHandler::extractUpdateCommand(const uint8_t* commandData, size_t size, UpdateParams& params) { - ReturnValue_t result = RETURN_OK; + size_t remSize = size; if (size > (config::MAX_FILENAME_SIZE + config::MAX_PATH_SIZE + sizeof(params.memId)) + - sizeof(params.startAddr)) { + sizeof(params.startAddr) + sizeof(params.bytesWritten) + sizeof(params.seqCount)) { sif::warning << "PlocSupervisorHandler::extractUpdateCommand: Data size too big" << std::endl; return SupvReturnValuesIF::INVALID_LENGTH; } - 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; - } - params.memId = *(commandData + params.file.size() + SIZE_NULL_TERMINATOR); - const uint8_t* startAddressPtr = - commandData + params.file.size() + SIZE_NULL_TERMINATOR + sizeof(params.memId); - size_t remainingSize = 10; - result = SerializeAdapter::deSerialize(¶ms.startAddr, &startAddressPtr, &remainingSize, - SerializeIF::Endianness::BIG); - if (result != RETURN_OK) { - sif::warning - << "PlocSupervisorHandler::extractUpdateCommand: Failed to deserialize start address" - << std::endl; - return result; - } - result = SerializeAdapter::deSerialize(¶ms.bytesWritten, &startAddressPtr, &remainingSize, + ReturnValue_t result = RETURN_OK; + result = extractBaseParams(&commandData, size, params); + result = SerializeAdapter::deSerialize(¶ms.bytesWritten, &commandData, &remSize, SerializeIF::Endianness::BIG); if (result != RETURN_OK) { sif::warning << "PlocSupervisorHandler::extractUpdateCommand: Failed to deserialize bytes " @@ -2029,7 +2007,7 @@ ReturnValue_t PlocSupervisorHandler::extractUpdateCommand(const uint8_t* command << std::endl; return result; } - result = SerializeAdapter::deSerialize(¶ms.seqCount, &startAddressPtr, &remainingSize, + result = SerializeAdapter::deSerialize(¶ms.seqCount, &commandData, &remSize, SerializeIF::Endianness::BIG); if (result != RETURN_OK) { sif::warning @@ -2040,6 +2018,38 @@ ReturnValue_t PlocSupervisorHandler::extractUpdateCommand(const uint8_t* command return RETURN_OK; } +ReturnValue_t PlocSupervisorHandler::extractBaseParams(const uint8_t** commandData, size_t& remSize, + UpdateParams& params) { + bool nullTermFound = false; + for (size_t idx = 0; idx < remSize; idx++) { + if ((*commandData)[idx] == '\0') { + nullTermFound = true; + break; + } + } + if (not nullTermFound) { + return HasReturnvaluesIF::RETURN_FAILED; + } + 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; + } + *commandData += params.file.size() + SIZE_NULL_TERMINATOR; + remSize -= (params.file.size() + SIZE_NULL_TERMINATOR); + params.memId = **commandData; + *commandData += 1; + remSize -= 1; + ReturnValue_t result = SerializeAdapter::deSerialize(¶ms.startAddr, commandData, &remSize, + SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + sif::warning << "PlocSupervisorHandler::extractBaseParams: Failed to deserialize start address" + << std::endl; + return result; + } + return result; +} + ReturnValue_t PlocSupervisorHandler::eventSubscription() { ReturnValue_t result = RETURN_OK; EventManagerIF* manager = ObjectManager::instance()->get(objects::EVENT_MANAGER); diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index 7f0b2574..e410340f 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -376,6 +376,8 @@ class PlocSupervisorHandler : public DeviceHandlerBase { }; ReturnValue_t extractUpdateCommand(const uint8_t* commandData, size_t size, UpdateParams& params); + ReturnValue_t extractBaseParams(const uint8_t** commandData, size_t& remSize, + UpdateParams& params); ReturnValue_t eventSubscription(); ReturnValue_t handleExecutionSuccessReport(const uint8_t* data); diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index b324b15b..36e3b392 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -58,9 +58,7 @@ ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { break; } case InternalState::CHECK_MEMORY: { - sif::info << "PlocSupvHelper::performUpdate: Memory Check" << std::endl; - result = handleCheckMemoryCommand(); - triggerEvent(SUPV_MEM_CHECK_STATUS, result); + executeFullCheckMemoryCommand(); internalState = InternalState::IDLE; break; } @@ -150,11 +148,18 @@ ReturnValue_t PlocSupvHelper::performUpdate(std::string file, uint8_t memoryId, return result; } +ReturnValue_t PlocSupvHelper::performMemCheck(std::string file, uint8_t memoryId, + uint32_t startAddress) { + update.file = file; + return performMemCheck(memoryId, startAddress, getFileSize(update.file), true); +} + ReturnValue_t PlocSupvHelper::performMemCheck(uint8_t memoryId, uint32_t startAddress, - size_t sizeToCheck) { + size_t sizeToCheck, bool checkCrc) { update.memoryId = memoryId; update.startAddress = startAddress; update.length = sizeToCheck; + update.crcShouldBeChecked = checkCrc; internalState = InternalState::CHECK_MEMORY; uartComIF->flushUartTxAndRxBuf(comCookie); semaphore.release(); @@ -185,6 +190,37 @@ ReturnValue_t PlocSupvHelper::startEventbBufferRequest(std::string path) { void PlocSupvHelper::stopProcess() { terminate = true; } +void PlocSupvHelper::executeFullCheckMemoryCommand() { + ReturnValue_t result; + if (update.crcShouldBeChecked) { + sif::info << "PlocSupvHelper::performUpdate: Calculating Image CRC" << std::endl; + result = calcImageCrc(); + if (result != RETURN_OK) { + triggerEvent(SUPV_MEM_CHECK_FAIL, result); + return; + } + } + sif::info << "PlocSupvHelper::executeFullCheckMemoryCommand: Selecting Memory" << std::endl; + result = selectMemory(); + if (result != RETURN_OK) { + triggerEvent(SUPV_MEM_CHECK_FAIL, result); + return; + } + sif::info << "PlocSupvHelper::executeFullCheckMemoryCommand: Preparing Update" << std::endl; + result = prepareUpdate(); + if (result != RETURN_OK) { + triggerEvent(SUPV_MEM_CHECK_FAIL, result); + return; + } + sif::info << "PlocSupvHelper::executeFullCheckMemoryCommand: Memory Check" << std::endl; + result = handleCheckMemoryCommand(); + if (result == HasReturnvaluesIF::RETURN_OK) { + triggerEvent(SUPV_MEM_CHECK_OK, result); + } else { + triggerEvent(SUPV_MEM_CHECK_FAIL, result); + } +} + ReturnValue_t PlocSupvHelper::performUpdate() { ReturnValue_t result = RETURN_OK; sif::info << "PlocSupvHelper::performUpdate: Calculating Image CRC" << std::endl; @@ -471,7 +507,7 @@ ReturnValue_t PlocSupvHelper::exeReportHandling() { } return result; } - return exeReportHandling(); + return result; } ReturnValue_t PlocSupvHelper::handleTmReception(size_t remainingBytes, uint8_t* readBuf, @@ -542,15 +578,19 @@ ReturnValue_t PlocSupvHelper::receive(uint8_t* data, size_t* readBytes, size_t r ReturnValue_t PlocSupvHelper::calcImageCrc() { ReturnValue_t result = RETURN_OK; + if (update.length == 0) { + return HasReturnvaluesIF::RETURN_FAILED; + } #ifdef XIPHOS_Q7S result = FilesystemHelper::checkPath(update.file); -#endif - auto crc16Calcer = etl::crc16_ccitt(); if (result != RETURN_OK) { sif::warning << "PlocSupvHelper::calcImageCrc: File " << update.file << " does not exist" << std::endl; return result; } +#endif + + auto crc16Calcer = etl::crc16_ccitt(); std::ifstream file(update.file, std::ifstream::binary); std::array crcBuf; #if OBSW_DEBUG_PLOC_SUPERVISOR == 1 @@ -586,7 +626,7 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { resetSpParams(); // Will hold status report for later processing std::array statusReportBuf{}; - supv::UpdateStatusReport updateStatusReport(statusReportBuf.data(), statusReportBuf.size()); + supv::UpdateStatusReport updateStatusReport(tmBuf.data(), tmBuf.size()); // Verification of update write procedure supv::CheckMemory packet(spParams); result = packet.buildPacket(update.memoryId, update.startAddress, update.length); @@ -611,7 +651,10 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { if (result != HasReturnvaluesIF::RETURN_OK) { sif::warning << "Reading exe failure report failed" << std::endl; } - return exeReportHandling(); + result = exeReportHandling(); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "Handling exe report failed" << std::endl; + } } else if (spReader.getApid() == supv::APID_UPDATE_STATUS_REPORT) { size_t remBytes = spReader.getPacketDataLen() + 1; result = handleTmReception(remBytes, tmBuf.data() + ccsds::HEADER_LEN); @@ -623,9 +666,11 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { } result = updateStatusReport.checkCrc(); if (result != RETURN_OK) { - sif::warning << "PlocSupvHelper::handleTmReception: CRC check failed" << std::endl; + 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()); } result = handleExe(CRC_EXECUTION_TIMEOUT); @@ -634,16 +679,20 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { } // Now process the status report + updateStatusReport.setData(statusReportBuf.data(), statusReportBuf.size()); result = updateStatusReport.parseDataField(); if (result != RETURN_OK) { return result; } - result = updateStatusReport.verifycrc(update.crc); - if (result != RETURN_OK) { - sif::warning << "PlocSupvHelper::handleCheckMemoryCommand: CRC failure. Expected CRC 0x" - << std::hex << update.crc << " but received CRC 0x" << updateStatusReport.getCrc() - << std::endl; - return result; + if (update.crcShouldBeChecked) { + result = updateStatusReport.verifycrc(update.crc); + if (result != RETURN_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; } diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 81cbfd1d..6be2ff68 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -94,7 +94,8 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha static constexpr Event SUPV_UPDATE_PROGRESS = MAKE_EVENT(22, severity::INFO); //! Status of memory check command //! P1: Returncode, 0 for success, other value with returncode for failure - static constexpr Event SUPV_MEM_CHECK_STATUS = MAKE_EVENT(23, severity::INFO); + static constexpr Event SUPV_MEM_CHECK_OK = MAKE_EVENT(23, severity::INFO); + static constexpr Event SUPV_MEM_CHECK_FAIL = MAKE_EVENT(24, severity::INFO); PlocSupvHelper(object_id_t objectId); virtual ~PlocSupvHelper(); @@ -118,7 +119,10 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha size_t startBytesWritten, uint16_t initSeqCount); ReturnValue_t startUpdate(std::string file, uint8_t memoryId, uint32_t startAddress); - ReturnValue_t performMemCheck(uint8_t memoryId, uint32_t startAddress, size_t sizeToCheck); + 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); + /** * @brief This initiate the continuation of a failed update. */ @@ -165,6 +169,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha // Size of update uint32_t length; uint32_t crc; + bool crcShouldBeChecked = false; // size_t remainingSize; size_t bytesWritten; uint32_t packetNum; @@ -211,6 +216,8 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha // Remembers APID to know at which command a procedure failed uint16_t rememberApid = 0; + void executeFullCheckMemoryCommand(); + ReturnValue_t performUpdate(); ReturnValue_t continueUpdate(); ReturnValue_t updateOperation(); diff --git a/tmtc b/tmtc index 425870d1..56514759 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 425870d16150f5b99e8e450ac892104e557aff20 +Subproject commit 56514759551204c20687c393f463e74204b821f2 From 51463700d542ac9afb388866624bdd1e649ef64e Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 22 Aug 2022 13:52:39 +0200 Subject: [PATCH 43/58] smaller bugfixes --- linux/devices/ploc/PlocSupvHelper.cpp | 1 + linux/devices/ploc/PlocSupvHelper.h | 3 +-- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 36e3b392..42464dc7 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -140,6 +140,7 @@ ReturnValue_t PlocSupvHelper::performUpdate(std::string file, uint8_t memoryId, update.startAddress = startAddress; update.progressPercent = 0; update.bytesWritten = startBytesWritten; + update.crcShouldBeChecked = true; update.packetNum = 1; update.sequenceCount = initSeqCount; internalState = InternalState::UPDATE; diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 6be2ff68..27eaaa94 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -169,8 +169,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha // Size of update uint32_t length; uint32_t crc; - bool crcShouldBeChecked = false; - // size_t remainingSize; + bool crcShouldBeChecked = true; size_t bytesWritten; uint32_t packetNum; uint16_t sequenceCount; From 519c7840cc8430dfd6d97428c21b394924351656 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 22 Aug 2022 15:09:05 +0200 Subject: [PATCH 44/58] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 56514759..3479f560 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 56514759551204c20687c393f463e74204b821f2 +Subproject commit 3479f5607d47c23ead50e29e169aa8480d114b70 From 64b2ceea0a6649be583a7723200b789b733bec5d Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 22 Aug 2022 17:09:39 +0200 Subject: [PATCH 45/58] set boot status report set valid --- linux/devices/ploc/PlocSupervisorHandler.cpp | 1 + tmtc | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 1e2a20f3..ff6eb624 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -1127,6 +1127,7 @@ ReturnValue_t PlocSupervisorHandler::handleBootStatusReport(const uint8_t* data) bootStatusReport.bootCycles = *(data + offset); nextReplyId = supv::EXE_REPORT; + bootStatusReport.setValidity(true, true); #if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_PLOC_SUPERVISOR == 1 sif::info << "PlocSupervisorHandler::handleBootStatusReport: SoC State (0 - off, 1 - booting, 2 " diff --git a/tmtc b/tmtc index 3479f560..bb23e4f0 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 3479f5607d47c23ead50e29e169aa8480d114b70 +Subproject commit bb23e4f02174080a12510296363e7c6456b19e58 From 42e3d92fb996ef40b0ca85ac5be8be7546574b1f Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 22 Aug 2022 17:10:19 +0200 Subject: [PATCH 46/58] set hk set valid as well --- linux/devices/ploc/PlocSupervisorHandler.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index ff6eb624..668264f1 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -1065,6 +1065,7 @@ ReturnValue_t PlocSupervisorHandler::handleHkReport(const uint8_t* data) { offset += 1; nextReplyId = supv::EXE_REPORT; + hkset.setValidity(true, true); #if OBSW_VERBOSE_LEVEL >= 1 && OBSW_DEBUG_PLOC_SUPERVISOR == 1 sif::info << "PlocSupervisorHandler::handleHkReport: temp_ps: " << hkset.tempPs << std::endl; From 84268c6dd601779082d7367be84d07de82fde78a Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 22 Aug 2022 17:35:32 +0200 Subject: [PATCH 47/58] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index bb23e4f0..13256211 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit bb23e4f02174080a12510296363e7c6456b19e58 +Subproject commit 1325621133158604880f9d609646dd29deb09f2a From 208856ef52f9b347994035df783c93aec5c26ef4 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 22 Aug 2022 21:44:18 +0200 Subject: [PATCH 48/58] bump tmtc again --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 13256211..7dfe92be 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 1325621133158604880f9d609646dd29deb09f2a +Subproject commit 7dfe92be8c85260e5abd1d52f9b201d26dbf6dc3 From e09eaae42f1d82f41c65a1f8812df0a84d32e9c9 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 22 Aug 2022 22:18:14 +0200 Subject: [PATCH 49/58] update events --- generators/bsp_q7s_events.csv | 33 ++++++------ generators/events/translateEvents.cpp | 53 ++++++++++--------- generators/objects/translateObjects.cpp | 2 +- linux/devices/ploc/PlocSupervisorHandler.cpp | 2 +- linux/devices/ploc/PlocSupvHelper.h | 39 +++++++------- linux/fsfwconfig/events/translateEvents.cpp | 53 ++++++++++--------- linux/fsfwconfig/objects/translateObjects.cpp | 2 +- tmtc | 2 +- 8 files changed, 97 insertions(+), 89 deletions(-) diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index 7d822e1d..fc8492ce 100644 --- a/generators/bsp_q7s_events.csv +++ b/generators/bsp_q7s_events.csv @@ -194,22 +194,23 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 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_SENDING_COMMAND_FAILED;LOW;;linux/devices/ploc/PlocSupvHelper.h -13609;0x3529;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 -13610;0x352a;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 -13611;0x352b;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 -13612;0x352c;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 -13613;0x352d;SUPV_ACK_FAILURE_REPORT;LOW;Supervisor received acknowledgment failure report P1: Internal state of supervisor helper;linux/devices/ploc/PlocSupvHelper.h -13614;0x352e;SUPV_EXE_FAILURE_REPORT;LOW;Execution report failure P1:;linux/devices/ploc/PlocSupvHelper.h -13615;0x352f;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 -13616;0x3530;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 -13617;0x3531;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 -13618;0x3532;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 -13619;0x3533;WRITE_MEMORY_FAILED;LOW;Update procedure failed when sending packet. P1: First byte percent, Third and Fourht bytes Sequence Count, P2: Bytes written;linux/devices/ploc/PlocSupvHelper.h -13620;0x3534;SUPV_REPLY_SIZE_MISSMATCH;LOW;;linux/devices/ploc/PlocSupvHelper.h -13621;0x3535;SUPV_REPLY_CRC_MISSMATCH;LOW;;linux/devices/ploc/PlocSupvHelper.h -13622;0x3536;SUPV_UPDATE_PROGRESS;INFO;Will be triggered every 5 percent of the update progress. P1: First byte percent, Third and Fourht bytes Sequence Count, P2: Bytes written;linux/devices/ploc/PlocSupvHelper.h -13623;0x3537;SUPV_MEM_CHECK_STATUS;INFO;;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 Fourht bytes 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 Fourht bytes Sequence Count, P2: Bytes written;linux/devices/ploc/PlocSupvHelper.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 f9511036..d4f6f594 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 215 translations. + * @brief Auto-generated event translation file. Contains 216 translations. * @details - * Generated on: 2022-08-22 12:35:41 + * Generated on: 2022-08-22 22:17:50 */ #include "translateEvents.h" @@ -196,6 +196,8 @@ 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"; @@ -211,7 +213,6 @@ 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 *SUPV_MEM_CHECK_STATUS_STRING = "SUPV_MEM_CHECK_STATUS"; const char *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; const char *REBOOT_SW_STRING = "REBOOT_SW"; const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED"; @@ -602,37 +603,39 @@ const char *translateEvents(Event event) { case (13607): return SUPV_EVENT_BUFFER_REQUEST_TERMINATED_STRING; case (13608): - return SUPV_SENDING_COMMAND_FAILED_STRING; + return SUPV_MEM_CHECK_OK_STRING; case (13609): - return SUPV_HELPER_REQUESTING_REPLY_FAILED_STRING; - case (13610): - return SUPV_HELPER_READING_REPLY_FAILED_STRING; - case (13611): - return SUPV_MISSING_ACK_STRING; - case (13612): - return SUPV_MISSING_EXE_STRING; - case (13613): - return SUPV_ACK_FAILURE_REPORT_STRING; - case (13614): - return SUPV_EXE_FAILURE_REPORT_STRING; - case (13615): - return SUPV_ACK_INVALID_APID_STRING; + return SUPV_MEM_CHECK_FAIL_STRING; case (13616): - return SUPV_EXE_INVALID_APID_STRING; + return SUPV_SENDING_COMMAND_FAILED_STRING; case (13617): - return ACK_RECEPTION_FAILURE_STRING; + return SUPV_HELPER_REQUESTING_REPLY_FAILED_STRING; case (13618): - return EXE_RECEPTION_FAILURE_STRING; + return SUPV_HELPER_READING_REPLY_FAILED_STRING; case (13619): - return WRITE_MEMORY_FAILED_STRING; + return SUPV_MISSING_ACK_STRING; case (13620): - return SUPV_REPLY_SIZE_MISSMATCH_STRING; + return SUPV_MISSING_EXE_STRING; case (13621): - return SUPV_REPLY_CRC_MISSMATCH_STRING; + return SUPV_ACK_FAILURE_REPORT_STRING; case (13622): - return SUPV_UPDATE_PROGRESS_STRING; + return SUPV_EXE_FAILURE_REPORT_STRING; case (13623): - return SUPV_MEM_CHECK_STATUS_STRING; + 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 (13700): return ALLOC_FAILURE_STRING; case (13701): diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index de55983c..b9535da0 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 133 translations. - * Generated on: 2022-08-22 12:35:41 + * Generated on: 2022-08-22 22:17:50 */ #include "translateObjects.h" diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index 668264f1..b2759e53 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -2068,7 +2068,7 @@ ReturnValue_t PlocSupervisorHandler::eventSubscription() { } result = manager->subscribeToEventRange( eventQueue->getId(), event::getEventId(PlocSupvHelper::SUPV_UPDATE_FAILED), - event::getEventId(PlocSupvHelper::SUPV_EVENT_BUFFER_REQUEST_TERMINATED)); + event::getEventId(PlocSupvHelper::SUPV_MEM_CHECK_FAIL)); if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "PlocSupervisorHandler::eventSubscritpion: Failed to subscribe to events from " diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 27eaaa94..abd43187 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -42,60 +42,61 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha //! [EXPORT] : [COMMENT] Terminated event buffer request by command //! P1: Number of packets read before process was terminated static const Event SUPV_EVENT_BUFFER_REQUEST_TERMINATED = MAKE_EVENT(7, severity::LOW); + //! Status of memory check command + //! P1: Returncode, 0 for success, other value with returncode for failure + static constexpr Event SUPV_MEM_CHECK_OK = MAKE_EVENT(8, severity::INFO); + static constexpr Event SUPV_MEM_CHECK_FAIL = MAKE_EVENT(9, severity::INFO); + //! [EXPORT] : [COMMENT] Communication interface returned failure when trying to send the command //! to the supervisor //! P1: Return value returned by the communication interface sendMessage function //! P2: Internal state of supervisor helper - static const Event SUPV_SENDING_COMMAND_FAILED = MAKE_EVENT(8, severity::LOW); + static const Event SUPV_SENDING_COMMAND_FAILED = MAKE_EVENT(16, severity::LOW); //! [EXPORT] : [COMMENT] Request receive message of communication interface failed //! P1: Return value returned by the communication interface requestReceiveMessage function //! P2: Internal state of supervisor helper - static const Event SUPV_HELPER_REQUESTING_REPLY_FAILED = MAKE_EVENT(9, severity::LOW); + static const Event SUPV_HELPER_REQUESTING_REPLY_FAILED = MAKE_EVENT(17, severity::LOW); //! [EXPORT] : [COMMENT] Reading receive message of communication interface failed //! P1: Return value returned by the communication interface readingReceivedMessage function //! P2: Internal state of supervisor helper - static const Event SUPV_HELPER_READING_REPLY_FAILED = MAKE_EVENT(10, severity::LOW); + static const Event SUPV_HELPER_READING_REPLY_FAILED = MAKE_EVENT(18, severity::LOW); //! [EXPORT] : [COMMENT] Did not receive acknowledgement report //! P1: Number of bytes missing //! P2: Internal state of MPSoC helper - static const Event SUPV_MISSING_ACK = MAKE_EVENT(11, severity::LOW); + static const Event SUPV_MISSING_ACK = MAKE_EVENT(19, severity::LOW); //! [EXPORT] : [COMMENT] Supervisor did not receive execution report //! P1: Number of bytes missing //! P2: Internal state of supervisor helper - static const Event SUPV_MISSING_EXE = MAKE_EVENT(12, severity::LOW); + static const Event SUPV_MISSING_EXE = MAKE_EVENT(20, severity::LOW); //! [EXPORT] : [COMMENT] Supervisor received acknowledgment failure report //! P1: Internal state of supervisor helper - static const Event SUPV_ACK_FAILURE_REPORT = MAKE_EVENT(13, severity::LOW); + static const Event SUPV_ACK_FAILURE_REPORT = MAKE_EVENT(21, severity::LOW); //! [EXPORT] : [COMMENT] Execution report failure //! P1: - static const Event SUPV_EXE_FAILURE_REPORT = MAKE_EVENT(14, severity::LOW); + static const Event SUPV_EXE_FAILURE_REPORT = MAKE_EVENT(22, severity::LOW); //! [EXPORT] : [COMMENT] Supervisor expected acknowledgment report but received space packet with //! other apid P1: Apid of received space packet P2: Internal state of supervisor helper - static const Event SUPV_ACK_INVALID_APID = MAKE_EVENT(15, severity::LOW); + static const Event SUPV_ACK_INVALID_APID = MAKE_EVENT(23, severity::LOW); //! [EXPORT] : [COMMENT] Supervisor helper expected execution report but received space packet //! with other apid P1: Apid of received space packet P2: Internal state of supervisor helper - static const Event SUPV_EXE_INVALID_APID = MAKE_EVENT(16, severity::LOW); + static const Event SUPV_EXE_INVALID_APID = MAKE_EVENT(24, severity::LOW); //! [EXPORT] : [COMMENT] Failed to receive acknowledgment report //! P1: Return value //! P2: Apid of command for which the reception of the acknowledgment report failed - static const Event ACK_RECEPTION_FAILURE = MAKE_EVENT(17, severity::LOW); + static const Event ACK_RECEPTION_FAILURE = MAKE_EVENT(25, severity::LOW); //! [EXPORT] : [COMMENT] Failed to receive execution report //! P1: Return value //! P2: Apid of command for which the reception of the execution report failed - static const Event EXE_RECEPTION_FAILURE = MAKE_EVENT(18, severity::LOW); + static const Event EXE_RECEPTION_FAILURE = MAKE_EVENT(26, severity::LOW); //! [EXPORT] : [COMMENT] Update procedure failed when sending packet. //! P1: First byte percent, Third and Fourht bytes Sequence Count, P2: Bytes written - static const Event WRITE_MEMORY_FAILED = MAKE_EVENT(19, severity::LOW); - static const Event SUPV_REPLY_SIZE_MISSMATCH = MAKE_EVENT(20, severity::LOW); - static const Event SUPV_REPLY_CRC_MISSMATCH = MAKE_EVENT(21, severity::LOW); + static const Event WRITE_MEMORY_FAILED = MAKE_EVENT(27, severity::LOW); + static const Event SUPV_REPLY_SIZE_MISSMATCH = MAKE_EVENT(28, severity::LOW); + static const Event SUPV_REPLY_CRC_MISSMATCH = MAKE_EVENT(29, severity::LOW); //! [EXPORT] : [COMMENT] Will be triggered every 5 percent of the update progress. //! P1: First byte percent, Third and Fourht bytes Sequence Count, P2: Bytes written - static constexpr Event SUPV_UPDATE_PROGRESS = MAKE_EVENT(22, severity::INFO); - //! Status of memory check command - //! P1: Returncode, 0 for success, other value with returncode for failure - static constexpr Event SUPV_MEM_CHECK_OK = MAKE_EVENT(23, severity::INFO); - static constexpr Event SUPV_MEM_CHECK_FAIL = MAKE_EVENT(24, severity::INFO); + static constexpr Event SUPV_UPDATE_PROGRESS = MAKE_EVENT(30, severity::INFO); PlocSupvHelper(object_id_t objectId); virtual ~PlocSupvHelper(); diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index f9511036..d4f6f594 100644 --- a/linux/fsfwconfig/events/translateEvents.cpp +++ b/linux/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** - * @brief Auto-generated event translation file. Contains 215 translations. + * @brief Auto-generated event translation file. Contains 216 translations. * @details - * Generated on: 2022-08-22 12:35:41 + * Generated on: 2022-08-22 22:17:50 */ #include "translateEvents.h" @@ -196,6 +196,8 @@ 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"; @@ -211,7 +213,6 @@ 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 *SUPV_MEM_CHECK_STATUS_STRING = "SUPV_MEM_CHECK_STATUS"; const char *ALLOC_FAILURE_STRING = "ALLOC_FAILURE"; const char *REBOOT_SW_STRING = "REBOOT_SW"; const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED"; @@ -602,37 +603,39 @@ const char *translateEvents(Event event) { case (13607): return SUPV_EVENT_BUFFER_REQUEST_TERMINATED_STRING; case (13608): - return SUPV_SENDING_COMMAND_FAILED_STRING; + return SUPV_MEM_CHECK_OK_STRING; case (13609): - return SUPV_HELPER_REQUESTING_REPLY_FAILED_STRING; - case (13610): - return SUPV_HELPER_READING_REPLY_FAILED_STRING; - case (13611): - return SUPV_MISSING_ACK_STRING; - case (13612): - return SUPV_MISSING_EXE_STRING; - case (13613): - return SUPV_ACK_FAILURE_REPORT_STRING; - case (13614): - return SUPV_EXE_FAILURE_REPORT_STRING; - case (13615): - return SUPV_ACK_INVALID_APID_STRING; + return SUPV_MEM_CHECK_FAIL_STRING; case (13616): - return SUPV_EXE_INVALID_APID_STRING; + return SUPV_SENDING_COMMAND_FAILED_STRING; case (13617): - return ACK_RECEPTION_FAILURE_STRING; + return SUPV_HELPER_REQUESTING_REPLY_FAILED_STRING; case (13618): - return EXE_RECEPTION_FAILURE_STRING; + return SUPV_HELPER_READING_REPLY_FAILED_STRING; case (13619): - return WRITE_MEMORY_FAILED_STRING; + return SUPV_MISSING_ACK_STRING; case (13620): - return SUPV_REPLY_SIZE_MISSMATCH_STRING; + return SUPV_MISSING_EXE_STRING; case (13621): - return SUPV_REPLY_CRC_MISSMATCH_STRING; + return SUPV_ACK_FAILURE_REPORT_STRING; case (13622): - return SUPV_UPDATE_PROGRESS_STRING; + return SUPV_EXE_FAILURE_REPORT_STRING; case (13623): - return SUPV_MEM_CHECK_STATUS_STRING; + 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 (13700): return ALLOC_FAILURE_STRING; case (13701): diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index de55983c..b9535da0 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 133 translations. - * Generated on: 2022-08-22 12:35:41 + * Generated on: 2022-08-22 22:17:50 */ #include "translateObjects.h" diff --git a/tmtc b/tmtc index 7dfe92be..61375956 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 7dfe92be8c85260e5abd1d52f9b201d26dbf6dc3 +Subproject commit 613759562ed855f692936bad5b25e8e2570dca52 From d7bc35ea458f272de1da17c5319fd5dffd8d7797 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Mon, 22 Aug 2022 22:25:22 +0200 Subject: [PATCH 50/58] crc check fails on mem 0 --- linux/devices/ploc/PlocSupervisorHandler.cpp | 6 +++--- linux/devices/ploc/PlocSupvHelper.cpp | 16 ++++++++-------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index b2759e53..b90fa721 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -2066,9 +2066,9 @@ ReturnValue_t PlocSupervisorHandler::eventSubscription() { if (result != RETURN_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(PlocSupvHelper::SUPV_UPDATE_FAILED), + event::getEventId(PlocSupvHelper::SUPV_MEM_CHECK_FAIL)); if (result != RETURN_OK) { #if FSFW_CPP_OSTREAM_ENABLED == 1 sif::warning << "PlocSupervisorHandler::eventSubscritpion: Failed to subscribe to events from " diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 42464dc7..6c195865 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -194,26 +194,26 @@ void PlocSupvHelper::stopProcess() { terminate = true; } void PlocSupvHelper::executeFullCheckMemoryCommand() { ReturnValue_t result; if (update.crcShouldBeChecked) { - sif::info << "PlocSupvHelper::performUpdate: Calculating Image CRC" << std::endl; + sif::info << "PLOC SUPV Mem Check: Calculating Image CRC" << std::endl; result = calcImageCrc(); if (result != RETURN_OK) { triggerEvent(SUPV_MEM_CHECK_FAIL, result); return; } } - sif::info << "PlocSupvHelper::executeFullCheckMemoryCommand: Selecting Memory" << std::endl; + sif::info << "PLOC SUPV Mem Check: Selecting Memory" << std::endl; result = selectMemory(); if (result != RETURN_OK) { triggerEvent(SUPV_MEM_CHECK_FAIL, result); return; } - sif::info << "PlocSupvHelper::executeFullCheckMemoryCommand: Preparing Update" << std::endl; + sif::info << "PLOC SUPV Mem Check: Preparing Update" << std::endl; result = prepareUpdate(); if (result != RETURN_OK) { triggerEvent(SUPV_MEM_CHECK_FAIL, result); return; } - sif::info << "PlocSupvHelper::executeFullCheckMemoryCommand: Memory Check" << std::endl; + sif::info << "PLOC SUPV Mem Check: Memory Check" << std::endl; result = handleCheckMemoryCommand(); if (result == HasReturnvaluesIF::RETURN_OK) { triggerEvent(SUPV_MEM_CHECK_OK, result); @@ -224,22 +224,22 @@ void PlocSupvHelper::executeFullCheckMemoryCommand() { ReturnValue_t PlocSupvHelper::performUpdate() { ReturnValue_t result = RETURN_OK; - sif::info << "PlocSupvHelper::performUpdate: Calculating Image CRC" << std::endl; + sif::info << "PLOC SUPV Update MPSoC: Calculating Image CRC" << std::endl; result = calcImageCrc(); if (result != RETURN_OK) { return result; } - sif::info << "PlocSupvHelper::performUpdate: Selecting Memory" << std::endl; + sif::info << "PLOC SUPV Update MPSoC: Selecting Memory" << std::endl; result = selectMemory(); if (result != RETURN_OK) { return result; } - sif::info << "PlocSupvHelper::performUpdate: Preparing Update" << std::endl; + sif::info << "PLOC SUPV Update MPSoC: Preparing Update" << std::endl; result = prepareUpdate(); if (result != RETURN_OK) { return result; } - sif::info << "PlocSupvHelper::performUpdate: Erasing Memory" << std::endl; + sif::info << "PLOC SUPV Update MPSoC: Erasing Memory" << std::endl; result = eraseMemory(); if (result != RETURN_OK) { return result; From 1aeebcc0ee2dd049de8adc22f66a8253c8d64ff4 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Tue, 23 Aug 2022 18:26:14 +0200 Subject: [PATCH 51/58] important bugfix for update conitnuation --- linux/devices/ploc/PlocSupvHelper.cpp | 37 +++++++++++++++++---------- linux/devices/ploc/PlocSupvHelper.h | 2 ++ tmtc | 2 +- 3 files changed, 26 insertions(+), 15 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 6c195865..836e7fc0 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -135,7 +135,13 @@ ReturnValue_t PlocSupvHelper::performUpdate(std::string file, uint8_t memoryId, } #endif update.file = file; - update.length = getFileSize(update.file); + update.fullFileSize = getFileSize(update.file); + if (startBytesWritten > update.fullFileSize) { + sif::warning << "Invalid start bytes counter " << startBytesWritten + << ", smaller than full file length" << update.fullFileSize << std::endl; + return HasReturnvaluesIF::RETURN_FAILED; + } + update.length = update.fullFileSize - startBytesWritten; update.memoryId = memoryId; update.startAddress = startAddress; update.progressPercent = 0; @@ -152,6 +158,7 @@ ReturnValue_t PlocSupvHelper::performUpdate(std::string file, uint8_t memoryId, 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); } @@ -268,20 +275,20 @@ ReturnValue_t PlocSupvHelper::updateOperation() { ReturnValue_t PlocSupvHelper::writeUpdatePackets() { ReturnValue_t result = RETURN_OK; #if OBSW_DEBUG_PLOC_SUPERVISOR == 1 - ProgressPrinter progressPrinter("Supervisor update", update.length, + ProgressPrinter progressPrinter("Supervisor update", update.fullFileSize, ProgressPrinter::HALF_PERCENT); #endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ uint8_t tempData[supv::WriteMemory::CHUNK_MAX + 1]{}; std::ifstream file(update.file, std::ifstream::binary); uint16_t dataLength = 0; ccsds::SequenceFlags seqFlags; - while (update.bytesWritten < update.length) { + while (update.bytesWritten < update.fullFileSize) { if (terminate) { terminate = false; triggerEvent(TERMINATED_UPDATE_PROCEDURE); return PROCESS_TERMINATED; } - size_t remainingSize = update.length - update.bytesWritten; + size_t remainingSize = update.fullFileSize - update.bytesWritten; bool lastSegment = false; if (remainingSize > supv::WriteMemory::CHUNK_MAX) { dataLength = supv::WriteMemory::CHUNK_MAX; @@ -309,7 +316,7 @@ ReturnValue_t PlocSupvHelper::writeUpdatePackets() { seqFlags = ccsds::SequenceFlags::CONTINUATION; } resetSpParams(); - float progress = static_cast(update.bytesWritten) / update.length; + float progress = static_cast(update.bytesWritten) / update.fullFileSize; uint8_t progPercent = std::floor(progress * 100); if (progPercent > update.progressPercent) { update.progressPercent = progPercent; @@ -410,7 +417,8 @@ ReturnValue_t PlocSupvHelper::eraseMemory() { ReturnValue_t result = RETURN_OK; resetSpParams(); supv::EraseMemory eraseMemory(spParams); - result = eraseMemory.buildPacket(update.memoryId, update.startAddress, update.length); + result = eraseMemory.buildPacket(update.memoryId, update.startAddress + update.bytesWritten, + update.length); if (result != RETURN_OK) { return result; } @@ -579,7 +587,7 @@ ReturnValue_t PlocSupvHelper::receive(uint8_t* data, size_t* readBytes, size_t r ReturnValue_t PlocSupvHelper::calcImageCrc() { ReturnValue_t result = RETURN_OK; - if (update.length == 0) { + if (update.fullFileSize == 0) { return HasReturnvaluesIF::RETURN_FAILED; } #ifdef XIPHOS_Q7S @@ -593,17 +601,19 @@ ReturnValue_t PlocSupvHelper::calcImageCrc() { auto crc16Calcer = etl::crc16_ccitt(); std::ifstream file(update.file, std::ifstream::binary); - std::array crcBuf; + std::array crcBuf{}; #if OBSW_DEBUG_PLOC_SUPERVISOR == 1 - ProgressPrinter progress("Supervisor update crc calculation", update.length, + ProgressPrinter progress("Supervisor update crc calculation", update.fullFileSize, ProgressPrinter::ONE_PERCENT); #endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ uint32_t byteCount = 0; - while (byteCount < update.length) { - size_t bytesToRead = 1024; - size_t remLen = update.length - byteCount; + size_t bytesToRead = 1024; + while (byteCount < update.fullFileSize) { + size_t remLen = update.fullFileSize - byteCount; if (remLen < 1024) { bytesToRead = remLen; + } else { + bytesToRead = 1024; } file.seekg(byteCount, file.beg); file.read(reinterpret_cast(crcBuf.data()), bytesToRead); @@ -617,7 +627,6 @@ ReturnValue_t PlocSupvHelper::calcImageCrc() { #if OBSW_DEBUG_PLOC_SUPERVISOR == 1 progress.print(byteCount); #endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */ - file.close(); update.crc = crc16Calcer.value(); return result; } @@ -630,7 +639,7 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { supv::UpdateStatusReport updateStatusReport(tmBuf.data(), tmBuf.size()); // Verification of update write procedure supv::CheckMemory packet(spParams); - result = packet.buildPacket(update.memoryId, update.startAddress, update.length); + result = packet.buildPacket(update.memoryId, update.startAddress, update.fullFileSize); if (result != RETURN_OK) { return result; } diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index abd43187..3fc60145 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -167,6 +167,8 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha uint32_t startAddress; // Absolute name of file containing update data std::string file; + // Length of full file + size_t fullFileSize; // Size of update uint32_t length; uint32_t crc; diff --git a/tmtc b/tmtc index 61375956..aec55035 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 613759562ed855f692936bad5b25e8e2570dca52 +Subproject commit aec55035d7602226a2e61845565c94b5ed8f561c From e561805f3aa45e73360725631eb5507f94b4c574 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 24 Aug 2022 12:02:16 +0200 Subject: [PATCH 52/58] update ploc supv helper --- .../PlocSupervisorDefinitions.h | 28 +++- linux/devices/ploc/PlocSupervisorHandler.cpp | 15 +- linux/devices/ploc/PlocSupervisorHandler.h | 13 +- linux/devices/ploc/PlocSupvHelper.cpp | 131 +++++++++++------- linux/devices/ploc/PlocSupvHelper.h | 9 +- tmtc | 2 +- 6 files changed, 126 insertions(+), 72 deletions(-) diff --git a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h index d36e4c0c..bfe23488 100644 --- a/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h +++ b/linux/devices/devicedefinitions/PlocSupervisorDefinitions.h @@ -160,6 +160,15 @@ 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; + uint32_t startAddr; + uint32_t bytesWritten; + uint16_t seqCount; + bool deleteMemory; +}; + enum PoolIds : lp_id_t { NUM_TMS, TEMP_PS, @@ -1247,11 +1256,14 @@ class DisableAutoTm : public ploc::SpTcBase { */ class RequestLoggingData : public ploc::SpTcBase { public: + /** + * Subapid + */ enum class Sa : uint8_t { - REQUEST_COUNTERS = 1, - REQUEST_EVENT_BUFFERS = 2, - CLEAR_COUNTERS = 3, - SET_LOGGING_TOPIC = 4 + REQUEST_COUNTERS = 1, /**< REQUEST_COUNTERS */ + REQUEST_EVENT_BUFFERS = 2, /**< REQUEST_EVENT_BUFFERS */ + CLEAR_COUNTERS = 3, /**< CLEAR_COUNTERS */ + SET_LOGGING_TOPIC = 4 /**< SET_LOGGING_TOPIC */ }; RequestLoggingData(ploc::SpTcParams params) : ploc::SpTcBase(params) { @@ -1260,6 +1272,11 @@ class RequestLoggingData : public ploc::SpTcBase { 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 != result::OK) { @@ -1659,7 +1676,8 @@ class ExecutionReport : public VerificationReport { } default: sif::warning << "ExecutionReport::printStatusInformation: Invalid status code: 0x" - << std::hex << static_cast(statusCode) << std::endl; + << std::hex << std::setfill('0') << std::setw(4) + << static_cast(statusCode) << std::dec << std::endl; break; } } diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index b90fa721..a5d3f3e2 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -121,8 +121,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId, if (result != RETURN_OK) { return result; } - result = supvHelper->performUpdate(params.file, params.memId, params.startAddr, - params.bytesWritten, params.seqCount); + result = supvHelper->performUpdate(params); if (result != RETURN_OK) { return result; } @@ -1992,7 +1991,7 @@ ReturnValue_t PlocSupervisorHandler::getTimeStampString(std::string& timeStamp) } ReturnValue_t PlocSupervisorHandler::extractUpdateCommand(const uint8_t* commandData, size_t size, - UpdateParams& params) { + supv::UpdateParams& params) { size_t remSize = size; if (size > (config::MAX_FILENAME_SIZE + config::MAX_PATH_SIZE + sizeof(params.memId)) + sizeof(params.startAddr) + sizeof(params.bytesWritten) + sizeof(params.seqCount)) { @@ -2017,11 +2016,19 @@ ReturnValue_t PlocSupervisorHandler::extractUpdateCommand(const uint8_t* command << std::endl; return result; } + result = SerializeAdapter::deSerialize(¶ms.deleteMemory, &commandData, &remSize, + SerializeIF::Endianness::BIG); + if (result != RETURN_OK) { + sif::warning + << "PlocSupervisorHandler::extractUpdateCommand: Failed to deserialize whether to delete " + "memory" << std::endl; + return result; + } return RETURN_OK; } ReturnValue_t PlocSupervisorHandler::extractBaseParams(const uint8_t** commandData, size_t& remSize, - UpdateParams& params) { + supv::UpdateParams& params) { bool nullTermFound = false; for (size_t idx = 0; idx < remSize; idx++) { if ((*commandData)[idx] == '\0') { diff --git a/linux/devices/ploc/PlocSupervisorHandler.h b/linux/devices/ploc/PlocSupervisorHandler.h index e410340f..bd4b0b9c 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.h +++ b/linux/devices/ploc/PlocSupervisorHandler.h @@ -367,17 +367,10 @@ class PlocSupervisorHandler : public DeviceHandlerBase { ReturnValue_t prepareSetShutdownTimeoutCmd(const uint8_t* commandData); - struct UpdateParams { - std::string file; - uint8_t memId; - uint32_t startAddr; - uint32_t bytesWritten; - uint16_t seqCount; - }; - - ReturnValue_t extractUpdateCommand(const uint8_t* commandData, size_t size, UpdateParams& params); + ReturnValue_t extractUpdateCommand(const uint8_t* commandData, size_t size, + supv::UpdateParams& params); ReturnValue_t extractBaseParams(const uint8_t** commandData, size_t& remSize, - UpdateParams& params); + supv::UpdateParams& params); ReturnValue_t eventSubscription(); ReturnValue_t handleExecutionSuccessReport(const uint8_t* data); diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index 836e7fc0..a33765b5 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -46,7 +46,7 @@ ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) { break; } case InternalState::UPDATE: { - result = performUpdate(); + result = executeUpdate(); if (result == RETURN_OK) { triggerEvent(SUPV_UPDATE_SUCCESSFUL, result); } else if (result == PROCESS_TERMINATED) { @@ -107,22 +107,28 @@ void PlocSupvHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_ ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId, uint32_t startAddress) { - return performUpdate(file, memoryId, startAddress, 0, 1); + supv::UpdateParams params; + params.file = file; + params.memId = memoryId; + params.startAddr = startAddress; + params.bytesWritten = 0; + params.seqCount = 1; + params.deleteMemory = true; + return performUpdate(params); } -ReturnValue_t PlocSupvHelper::performUpdate(std::string file, uint8_t memoryId, - uint32_t startAddress, size_t startBytesWritten, - uint16_t initSeqCount) { +ReturnValue_t PlocSupvHelper::performUpdate(const supv::UpdateParams& params) { ReturnValue_t result = RETURN_OK; #ifdef XIPHOS_Q7S - result = FilesystemHelper::checkPath(file); + result = FilesystemHelper::checkPath(params.file); if (result != RETURN_OK) { - sif::warning << "PlocSupvHelper::startUpdate: File " << file << " does not exist" << std::endl; + sif::warning << "PlocSupvHelper::startUpdate: File " << params.file << " does not exist" + << std::endl; return result; } - result = FilesystemHelper::fileExists(file); + result = FilesystemHelper::fileExists(params.file); if (result != RETURN_OK) { - sif::warning << "PlocSupvHelper::startUpdate: The file " << file << " does not exist" + sif::warning << "PlocSupvHelper::startUpdate: The file " << params.file << " does not exist" << std::endl; return result; } @@ -134,21 +140,22 @@ ReturnValue_t PlocSupvHelper::performUpdate(std::string file, uint8_t memoryId, return RETURN_FAILED; } #endif - update.file = file; + update.file = params.file; update.fullFileSize = getFileSize(update.file); - if (startBytesWritten > update.fullFileSize) { - sif::warning << "Invalid start bytes counter " << startBytesWritten + if (params.bytesWritten > update.fullFileSize) { + sif::warning << "Invalid start bytes counter " << params.bytesWritten << ", smaller than full file length" << update.fullFileSize << std::endl; return HasReturnvaluesIF::RETURN_FAILED; } - update.length = update.fullFileSize - startBytesWritten; - update.memoryId = memoryId; - update.startAddress = startAddress; + update.length = update.fullFileSize - params.bytesWritten; + update.memoryId = params.memId; + update.startAddress = params.startAddr; update.progressPercent = 0; - update.bytesWritten = startBytesWritten; + update.bytesWritten = params.bytesWritten; update.crcShouldBeChecked = true; update.packetNum = 1; - update.sequenceCount = initSeqCount; + update.deleteMemory = params.deleteMemory; + update.sequenceCount = params.seqCount; internalState = InternalState::UPDATE; uartComIF->flushUartTxAndRxBuf(comCookie); semaphore.release(); @@ -229,7 +236,7 @@ void PlocSupvHelper::executeFullCheckMemoryCommand() { } } -ReturnValue_t PlocSupvHelper::performUpdate() { +ReturnValue_t PlocSupvHelper::executeUpdate() { ReturnValue_t result = RETURN_OK; sif::info << "PLOC SUPV Update MPSoC: Calculating Image CRC" << std::endl; result = calcImageCrc(); @@ -246,10 +253,12 @@ ReturnValue_t PlocSupvHelper::performUpdate() { if (result != RETURN_OK) { return result; } - sif::info << "PLOC SUPV Update MPSoC: Erasing Memory" << std::endl; - result = eraseMemory(); - if (result != RETURN_OK) { - return result; + if(update.deleteMemory) { + sif::info << "PLOC SUPV Update MPSoC: Erasing Memory" << std::endl; + result = eraseMemory(); + if (result != RETURN_OK) { + return result; + } } return updateOperation(); } @@ -372,13 +381,38 @@ ReturnValue_t PlocSupvHelper::performEventBufferRequest() { if (result != RETURN_OK) { return result; } - result = handleEventBufferReception(); + result = + handleTmReception(ccsds::HEADER_LEN, tmBuf.data(), supv::recv_timeout::UPDATE_STATUS_REPORT); if (result != RETURN_OK) { return result; } - result = handleExe(); - if (result != RETURN_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 != RETURN_OK) { + return result; + } + } + return result; +} + +ReturnValue_t PlocSupvHelper::handleRemainingExeReport(ploc::SpTmReader& reader) { + size_t remBytes = reader.getPacketDataLen() + 1; + ReturnValue_t result = handleTmReception(remBytes, tmBuf.data() + ccsds::HEADER_LEN); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "Reading exe failure report failed" << std::endl; + } + result = exeReportHandling(); + if (result != HasReturnvaluesIF::RETURN_OK) { + sif::warning << "Handling exe report failed" << std::endl; } return result; } @@ -652,22 +686,17 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { return result; } - result = - handleTmReception(ccsds::HEADER_LEN, tmBuf.data(), supv::recv_timeout::UPDATE_STATUS_REPORT); - SpacePacketReader spReader(tmBuf.data(), tmBuf.size()); + bool exeAlreadyHandled = false; + uint32_t timeout = std::max(CRC_EXECUTION_TIMEOUT, supv::recv_timeout::UPDATE_STATUS_REPORT); + result = handleTmReception(ccsds::HEADER_LEN, tmBuf.data(), timeout); + ploc::SpTmReader spReader(tmBuf.data(), tmBuf.size()); if (spReader.getApid() == supv::APID_EXE_FAILURE) { - size_t remBytes = spReader.getPacketDataLen() + 1; - result = handleTmReception(remBytes, tmBuf.data() + ccsds::HEADER_LEN); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "Reading exe failure report failed" << std::endl; - } - result = exeReportHandling(); - if (result != HasReturnvaluesIF::RETURN_OK) { - sif::warning << "Handling exe report failed" << std::endl; - } + 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); + result = handleTmReception(remBytes, tmBuf.data() + ccsds::HEADER_LEN, + supv::recv_timeout::UPDATE_STATUS_REPORT); if (result != RETURN_OK) { sif::warning << "PlocSupvHelper::handleCheckMemoryCommand: Failed to receive update status report" @@ -683,9 +712,11 @@ ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() { std::memcpy(statusReportBuf.data(), tmBuf.data(), updateStatusReport.getNominalSize()); } - result = handleExe(CRC_EXECUTION_TIMEOUT); - if (result != RETURN_OK) { - return result; + if (not exeAlreadyHandled) { + result = handleExe(CRC_EXECUTION_TIMEOUT); + if (result != RETURN_OK) { + return result; + } } // Now process the status report @@ -715,14 +746,14 @@ uint32_t PlocSupvHelper::getFileSize(std::string filename) { return size; } -ReturnValue_t PlocSupvHelper::handleEventBufferReception() { +ReturnValue_t PlocSupvHelper::handleEventBufferReception(ploc::SpTmReader& reader) { ReturnValue_t result = RETURN_OK; 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; - ploc::SpTmReader tmReader(tmBuf.data(), tmBuf.size()); + bool firstPacket = true; for (packetsRead = 0; packetsRead < NUM_EVENT_BUFFER_PACKETS; packetsRead++) { if (terminate) { triggerEvent(SUPV_EVENT_BUFFER_REQUEST_TERMINATED, packetsRead - 1); @@ -734,6 +765,10 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception() { } else { requestLen = SIZE_EVENT_BUFFER_FULL_PACKET; } + if (firstPacket) { + firstPacket = false; + requestLen -= 6; + } result = handleTmReception(requestLen); if (result != RETURN_OK) { sif::debug << "PlocSupvHelper::handleEventBufferReception: Failed while trying to read packet" @@ -741,20 +776,20 @@ ReturnValue_t PlocSupvHelper::handleEventBufferReception() { file.close(); return result; } - ReturnValue_t result = tmReader.checkCrc(); + ReturnValue_t result = reader.checkCrc(); if (result != RETURN_OK) { triggerEvent(SUPV_REPLY_CRC_MISSMATCH, rememberApid); return result; } - uint16_t apid = tmReader.getApid(); + uint16_t apid = reader.getApid(); if (apid != supv::APID_MRAM_DUMP_TM) { sif::warning << "PlocSupvHelper::handleEventBufferReception: Did not expect space packet " << "with APID 0x" << std::hex << apid << std::endl; file.close(); return EVENT_BUFFER_REPLY_INVALID_APID; } - file.write(reinterpret_cast(tmReader.getPacketData()), - tmReader.getPayloadDataLength()); + file.write(reinterpret_cast(reader.getPacketData()), + reader.getPayloadDataLength()); } return result; } diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index 3fc60145..c79af01f 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -116,8 +116,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha * * @return RETURN_OK if successful, otherwise error return value */ - ReturnValue_t performUpdate(std::string file, uint8_t memoryId, uint32_t startAddress, - size_t startBytesWritten, uint16_t initSeqCount); + 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, @@ -177,6 +176,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha uint32_t packetNum; uint16_t sequenceCount; uint8_t progressPercent; + bool deleteMemory = false; }; struct Update update; @@ -220,7 +220,7 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha void executeFullCheckMemoryCommand(); - ReturnValue_t performUpdate(); + ReturnValue_t executeUpdate(); ReturnValue_t continueUpdate(); ReturnValue_t updateOperation(); ReturnValue_t writeUpdatePackets(); @@ -268,7 +268,8 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha * @return The size of the file */ uint32_t getFileSize(std::string filename); - ReturnValue_t handleEventBufferReception(); + ReturnValue_t handleEventBufferReception(ploc::SpTmReader& reader); + ReturnValue_t handleRemainingExeReport(ploc::SpTmReader& reader); void resetSpParams(); }; diff --git a/tmtc b/tmtc index aec55035..ac782157 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit aec55035d7602226a2e61845565c94b5ed8f561c +Subproject commit ac7821575c16b2c08740722f8d9ae0b456c60ece From ef92673e4ed69635d87dda45c65fff7c929de02e Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 24 Aug 2022 12:07:55 +0200 Subject: [PATCH 53/58] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index ac782157..7885b29d 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit ac7821575c16b2c08740722f8d9ae0b456c60ece +Subproject commit 7885b29d22f23f0e4432126dd6c1d22b592428cc From 86bfa85e00c5c1dbeb6d881871190de2f3428cfe Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 24 Aug 2022 14:59:52 +0200 Subject: [PATCH 54/58] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index 13256211..aadcd2b0 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 1325621133158604880f9d609646dd29deb09f2a +Subproject commit aadcd2b061e89cee1533a173268859d08baedd91 From 6d53a38f9ff7de4c0086f0da0acf68bd4fe78d86 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 24 Aug 2022 15:16:46 +0200 Subject: [PATCH 55/58] small update --- linux/devices/ploc/PlocSupervisorHandler.cpp | 12 ++++++++---- linux/devices/ploc/PlocSupvHelper.cpp | 2 +- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/linux/devices/ploc/PlocSupervisorHandler.cpp b/linux/devices/ploc/PlocSupervisorHandler.cpp index a5d3f3e2..040fa1de 100644 --- a/linux/devices/ploc/PlocSupervisorHandler.cpp +++ b/linux/devices/ploc/PlocSupervisorHandler.cpp @@ -1994,7 +1994,8 @@ ReturnValue_t PlocSupervisorHandler::extractUpdateCommand(const uint8_t* command supv::UpdateParams& params) { size_t remSize = size; if (size > (config::MAX_FILENAME_SIZE + config::MAX_PATH_SIZE + sizeof(params.memId)) + - sizeof(params.startAddr) + sizeof(params.bytesWritten) + sizeof(params.seqCount)) { + 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; } @@ -2016,14 +2017,17 @@ ReturnValue_t PlocSupervisorHandler::extractUpdateCommand(const uint8_t* command << std::endl; return result; } - result = SerializeAdapter::deSerialize(¶ms.deleteMemory, &commandData, &remSize, - SerializeIF::Endianness::BIG); + uint8_t delMemRaw = 0; + result = SerializeAdapter::deSerialize(&delMemRaw, &commandData, &remSize, + SerializeIF::Endianness::BIG); if (result != RETURN_OK) { sif::warning << "PlocSupervisorHandler::extractUpdateCommand: Failed to deserialize whether to delete " - "memory" << std::endl; + "memory" + << std::endl; return result; } + params.deleteMemory = delMemRaw; return RETURN_OK; } diff --git a/linux/devices/ploc/PlocSupvHelper.cpp b/linux/devices/ploc/PlocSupvHelper.cpp index a33765b5..c6641f6e 100644 --- a/linux/devices/ploc/PlocSupvHelper.cpp +++ b/linux/devices/ploc/PlocSupvHelper.cpp @@ -253,7 +253,7 @@ ReturnValue_t PlocSupvHelper::executeUpdate() { if (result != RETURN_OK) { return result; } - if(update.deleteMemory) { + if (update.deleteMemory) { sif::info << "PLOC SUPV Update MPSoC: Erasing Memory" << std::endl; result = eraseMemory(); if (result != RETURN_OK) { From 920545b7090e9abc782c42484d1321d1cb80dbcf Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 24 Aug 2022 15:24:57 +0200 Subject: [PATCH 56/58] comment typo fix --- linux/devices/ploc/PlocSupvHelper.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/linux/devices/ploc/PlocSupvHelper.h b/linux/devices/ploc/PlocSupvHelper.h index c79af01f..fb585e12 100644 --- a/linux/devices/ploc/PlocSupvHelper.h +++ b/linux/devices/ploc/PlocSupvHelper.h @@ -89,13 +89,13 @@ class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public Ha //! P2: Apid of command for which the reception of the execution report failed static const Event EXE_RECEPTION_FAILURE = MAKE_EVENT(26, severity::LOW); //! [EXPORT] : [COMMENT] Update procedure failed when sending packet. - //! P1: First byte percent, Third and Fourht bytes Sequence Count, P2: Bytes written + //! P1: First byte percent, third and fourth byte Sequence Count, P2: Bytes written static const Event WRITE_MEMORY_FAILED = MAKE_EVENT(27, severity::LOW); static const Event SUPV_REPLY_SIZE_MISSMATCH = MAKE_EVENT(28, severity::LOW); static const Event SUPV_REPLY_CRC_MISSMATCH = MAKE_EVENT(29, severity::LOW); //! [EXPORT] : [COMMENT] Will be triggered every 5 percent of the update progress. - //! P1: First byte percent, Third and Fourht bytes Sequence Count, P2: Bytes written + //! 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); From 85172616f8a0d2a5ddb5a83f82fa2fd96ee04e71 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 24 Aug 2022 16:25:09 +0200 Subject: [PATCH 57/58] bump tmtc --- tmtc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tmtc b/tmtc index aadcd2b0..3151557b 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit aadcd2b061e89cee1533a173268859d08baedd91 +Subproject commit 3151557b1d3939a8123e79b277af70a674f49ae7 From 0d0f32b75154a00afe0949a5ded2596c15cb4db6 Mon Sep 17 00:00:00 2001 From: Robin Mueller Date: Wed, 24 Aug 2022 16:46:13 +0200 Subject: [PATCH 58/58] re-run generators --- generators/bsp_q7s_events.csv | 4 +- generators/bsp_q7s_returnvalues.csv | 634 +++++++++--------- generators/events/translateEvents.cpp | 2 +- generators/objects/translateObjects.cpp | 2 +- linux/fsfwconfig/events/translateEvents.cpp | 2 +- linux/fsfwconfig/objects/translateObjects.cpp | 2 +- tmtc | 2 +- 7 files changed, 324 insertions(+), 324 deletions(-) diff --git a/generators/bsp_q7s_events.csv b/generators/bsp_q7s_events.csv index fc8492ce..d4258731 100644 --- a/generators/bsp_q7s_events.csv +++ b/generators/bsp_q7s_events.csv @@ -207,10 +207,10 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path 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 Fourht bytes Sequence Count, P2: Bytes written;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 Fourht bytes Sequence Count, P2: Bytes written;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 13700;0x3584;ALLOC_FAILURE;MEDIUM;;bsp_q7s/core/CoreController.h 13701;0x3585;REBOOT_SW;MEDIUM; Software reboot occurred. Can also be a systemd reboot. P1: Current Chip, P2: Current Copy;bsp_q7s/core/CoreController.h 13702;0x3586;REBOOT_MECHANISM_TRIGGERED;MEDIUM;The reboot mechanism was triggered. P1: First 16 bits: Last Chip, Last 16 bits: Last Copy, P2: Each byte is the respective reboot count for the slots;bsp_q7s/core/CoreController.h diff --git a/generators/bsp_q7s_returnvalues.csv b/generators/bsp_q7s_returnvalues.csv index 1c99ffdc..ab196298 100644 --- a/generators/bsp_q7s_returnvalues.csv +++ b/generators/bsp_q7s_returnvalues.csv @@ -1,13 +1,14 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x0000;OK;System-wide code for ok.;0;HasReturnvaluesIF;fsfw/returnvalues/HasReturnvaluesIF.h 0x0001;Failed;Unspecified system-wide code for failed.;1;HasReturnvaluesIF;fsfw/returnvalues/HasReturnvaluesIF.h -0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CCSDSHandler.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 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,13 +21,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 +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 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 @@ -44,129 +44,126 @@ 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/CCSDSHandler.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/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 +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 +0x4300;FILS_GenericFileError;;0;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4301;FILS_IsBusy;;1;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4302;FILS_InvalidParameters;;2;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4305;FILS_FileDoesNotExist;;5;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4306;FILS_FileAlreadyExists;;6;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4307;FILS_FileLocked;;7;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x430a;FILS_DirectoryDoesNotExist;;10;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x430b;FILS_DirectoryAlreadyExists;;11;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x430c;FILS_DirectoryNotEmpty;;12;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x430f;FILS_SequencePacketMissingWrite;;15;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h +0x4310;FILS_SequencePacketMissingRead;;16;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.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 +0x1101;AL_Full;;1;ARRAY_LIST;fsfw/src/fsfw/container/ArrayList.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 +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/TcDistributor.h -0x1c02;TCD_DestinationNotFound;;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h -0x1c03;TCD_ServiceIdAlreadyExists;;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h -0x1b00;TCC_InvalidCcsdsVersion;;0;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b01;TCC_InvalidApid;;1;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b02;TCC_InvalidPacketType;;2;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b03;TCC_InvalidSecHeaderField;;3;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b04;TCC_IncorrectPrimaryHeader;;4;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b05;TCC_IncompletePacket;;5;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b06;TCC_InvalidPusVersion;;6;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b07;TCC_IncorrectChecksum;;7;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b08;TCC_IllegalPacketSubtype;;8;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h -0x1b09;TCC_IncorrectSecondaryHeader;;9;PACKET_CHECK;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 @@ -207,93 +204,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_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_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_InvalidDirectiveFields;;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_FinishedCantParseFsResponses;;6;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 -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 @@ -302,39 +215,19 @@ 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/TcDistributor.h +0x1c02;TCD_DestinationNotFound;;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h +0x1c03;TCD_ServiceIdAlreadyExists;;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributor.h +0x1b00;TCC_InvalidCcsdsVersion;;0;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b01;TCC_InvalidApid;;1;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b02;TCC_InvalidPacketType;;2;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b03;TCC_InvalidSecHeaderField;;3;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b04;TCC_IncorrectPrimaryHeader;;4;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b05;TCC_IncompletePacket;;5;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b06;TCC_InvalidPusVersion;;6;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b07;TCC_IncorrectChecksum;;7;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b08;TCC_IllegalPacketSubtype;;8;PACKET_CHECK;fsfw/src/fsfw/tcdistribution/definitions.h +0x1b09;TCC_IncorrectSecondaryHeader;;9;PACKET_CHECK;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 @@ -342,6 +235,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 +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 @@ -360,44 +323,52 @@ 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_InvalidDirectiveFields;;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_FinishedCantParseFsResponses;;6;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 +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_TimeshiftingNotPossible;;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4203;PUS11_InvalidRelativeTime;;3;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h -0x4300;FILS_GenericFileError;;0;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4301;FILS_IsBusy;;1;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4302;FILS_InvalidParameters;;2;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4305;FILS_FileDoesNotExist;;5;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4306;FILS_FileAlreadyExists;;6;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4307;FILS_FileLocked;;7;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x430a;FILS_DirectoryDoesNotExist;;10;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x430b;FILS_DirectoryAlreadyExists;;11;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x430c;FILS_DirectoryNotEmpty;;12;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x430f;FILS_SequencePacketMissingWrite;;15;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.h -0x4310;FILS_SequencePacketMissingRead;;16;FILE_SYSTEM;fsfw/src/fsfw/memory/HasFileSystemIF.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 @@ -407,12 +378,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 @@ -434,28 +405,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_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 +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/memory/FilesystemHelper.h 0x64a1;FSHLP_FileNotExists;Specified file does not exist on filesystem;161;FILE_SYSTEM_HELPER;bsp_q7s/memory/FilesystemHelper.h 0x6a00;SDMA_OpOngoing;;0;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h @@ -468,4 +469,3 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path 0x6a0d;SDMA_UnmountError;;13;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h 0x6a0e;SDMA_SystemCallError;;14;SD_CARD_MANAGER;bsp_q7s/memory/SdCardManager.h 0x6a0f;SDMA_PopenCallError;;15;SD_CARD_MANAGER;bsp_q7s/memory/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 d4f6f594..21ba77b3 100644 --- a/generators/events/translateEvents.cpp +++ b/generators/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** * @brief Auto-generated event translation file. Contains 216 translations. * @details - * Generated on: 2022-08-22 22:17:50 + * Generated on: 2022-08-24 16:44:18 */ #include "translateEvents.h" diff --git a/generators/objects/translateObjects.cpp b/generators/objects/translateObjects.cpp index b9535da0..12e74bfe 100644 --- a/generators/objects/translateObjects.cpp +++ b/generators/objects/translateObjects.cpp @@ -2,7 +2,7 @@ * @brief Auto-generated object translation file. * @details * Contains 133 translations. - * Generated on: 2022-08-22 22:17:50 + * Generated on: 2022-08-24 16:44:18 */ #include "translateObjects.h" diff --git a/linux/fsfwconfig/events/translateEvents.cpp b/linux/fsfwconfig/events/translateEvents.cpp index d4f6f594..21ba77b3 100644 --- a/linux/fsfwconfig/events/translateEvents.cpp +++ b/linux/fsfwconfig/events/translateEvents.cpp @@ -1,7 +1,7 @@ /** * @brief Auto-generated event translation file. Contains 216 translations. * @details - * Generated on: 2022-08-22 22:17:50 + * Generated on: 2022-08-24 16:44:18 */ #include "translateEvents.h" diff --git a/linux/fsfwconfig/objects/translateObjects.cpp b/linux/fsfwconfig/objects/translateObjects.cpp index b9535da0..12e74bfe 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 133 translations. - * Generated on: 2022-08-22 22:17:50 + * Generated on: 2022-08-24 16:44:18 */ #include "translateObjects.h" diff --git a/tmtc b/tmtc index 3151557b..d19cdfa5 160000 --- a/tmtc +++ b/tmtc @@ -1 +1 @@ -Subproject commit 3151557b1d3939a8123e79b277af70a674f49ae7 +Subproject commit d19cdfa5663966548918091005c7e9bc912e4041