Persistent TM Store #320

Merged
muellerr merged 109 commits from mueller/pus-15-tm-storage into develop 2023-02-24 19:03:39 +01:00
55 changed files with 2324 additions and 1422 deletions
Showing only changes of commit 12c5a10662 - Show all commits

View File

@ -17,8 +17,53 @@ change warranting a new major release:
# [unreleased] # [unreleased]
# [v1.28.0] 2023-02-17
eive-tmtc: v2.12.7
## Added
- In case the ACS Controller does recognize more than one RW to be invalid and therefore not
available, it does not perform pointing control but aborts shortly after `sensorProcessing`. If the
problem persits for 5 ACS cycles, the `MULTIPLE_RW_INVALID` event is triggered, which invokes the
transition of the `AcsSubsystem` to safe mode.
## Changed ## Changed
- Igrf13 model vector now outputs as uT instead of nT
- Changed timings for `AcsPst`, more time for sun sensors.
- Added values for MGM sensor fusion
- Refactored RW Software: Polling runs in separate thread, all RWs are now polled in under 60 ms.
PR: https://egit.irs.uni-stuttgart.de/eive/eive-obsw/pulls/381
- Bumped FSFW to allow initializing child modes in `SubsystemBase` derived objects.
## Fixed
- Fixed values for GYR sensor fusion
- Fixed speed types for `rwHandlingParameter`
- Pseudo inverse used for allocating torque to RWs and RW antistiction now actually consider the
state of the RWs
# [v1.27.2] 2023-02-14
Reaction Wheel handling was determined to be (quasi) broken and needs to be fixed in future release
to be usable by ACS controller.
eive-tmtc: v2.12.6
## Added
- Function for the ACS controller to command MTQ and RWs called by all subroutines
- RwHandler now handles commanding of RW speeds via RwSpeedActuationSet
- Tracing supports which allows checking whether threads are running as usual.
## Changed
- Remove 2 TCS threads.
- Move low level polling into ACS PST, move high level device handlers into TCS system task.
- ActCmds now returns command vectors as integers as required by the actuators
and scales them to the appropriate range
- All RwHandler are now polled five times per ACS cycle
- Remove 2 TCS threads. Move low level polling into ACS PST, move high level device handlers into - Remove 2 TCS threads. Move low level polling into ACS PST, move high level device handlers into
TCS system task. TCS system task.
- Further reduce number of threads: - Further reduce number of threads:
@ -27,10 +72,6 @@ change warranting a new major release:
3. Group all other components into PUS medium priority task 3. Group all other components into PUS medium priority task
4. Add SCEX device handler to PL task, remove dedicated thread 4. Add SCEX device handler to PL task, remove dedicated thread
## Added
- Tracing supports which allows checking whether threads are running as usual.
## Removed ## Removed
- lwgps dependency not compiled anymore, is not used - lwgps dependency not compiled anymore, is not used

View File

@ -10,8 +10,8 @@
cmake_minimum_required(VERSION 3.13) cmake_minimum_required(VERSION 3.13)
set(OBSW_VERSION_MAJOR 1) set(OBSW_VERSION_MAJOR 1)
set(OBSW_VERSION_MINOR 27) set(OBSW_VERSION_MINOR 28)
set(OBSW_VERSION_REVISION 1) set(OBSW_VERSION_REVISION 0)
# set(CMAKE_VERBOSE TRUE) # set(CMAKE_VERBOSE TRUE)

View File

@ -1,7 +1,7 @@
/** /**
* @brief Auto-generated event translation file. Contains 256 translations. * @brief Auto-generated event translation file. Contains 256 translations.
* @details * @details
* Generated on: 2023-02-13 10:07:30 * Generated on: 2023-02-17 02:12:04
*/ */
#include "translateEvents.h" #include "translateEvents.h"

View File

@ -2,7 +2,7 @@
* @brief Auto-generated object translation file. * @brief Auto-generated object translation file.
* @details * @details
* Contains 147 translations. * Contains 147 translations.
* Generated on: 2023-02-13 10:07:30 * Generated on: 2023-02-17 02:12:04
*/ */
#include "translateObjects.h" #include "translateObjects.h"

View File

@ -76,7 +76,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen
if (write(fileDescriptor, writeBuffer, writeSize) != static_cast<ssize_t>(writeSize)) { if (write(fileDescriptor, writeBuffer, writeSize) != static_cast<ssize_t>(writeSize)) {
sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl; sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl;
closeSpi(fileDescriptor, gpioId, &gpioIF, mutex); closeSpi(fileDescriptor, gpioId, &gpioIF, mutex);
return RwHandler::SPI_WRITE_FAILURE; return rws::SPI_WRITE_FAILURE;
} }
/** Encoding and sending command */ /** Encoding and sending command */
@ -101,7 +101,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen
if (write(fileDescriptor, writeBuffer, writeSize) != static_cast<ssize_t>(writeSize)) { if (write(fileDescriptor, writeBuffer, writeSize) != static_cast<ssize_t>(writeSize)) {
sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl; sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl;
closeSpi(fileDescriptor, gpioId, &gpioIF, mutex); closeSpi(fileDescriptor, gpioId, &gpioIF, mutex);
return RwHandler::SPI_WRITE_FAILURE; return rws::SPI_WRITE_FAILURE;
} }
idx++; idx++;
} }
@ -113,7 +113,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen
if (write(fileDescriptor, writeBuffer, writeSize) != static_cast<ssize_t>(writeSize)) { if (write(fileDescriptor, writeBuffer, writeSize) != static_cast<ssize_t>(writeSize)) {
sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl; sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl;
closeSpi(fileDescriptor, gpioId, &gpioIF, mutex); closeSpi(fileDescriptor, gpioId, &gpioIF, mutex);
return RwHandler::SPI_WRITE_FAILURE; return rws::SPI_WRITE_FAILURE;
} }
uint8_t* rxBuf = nullptr; uint8_t* rxBuf = nullptr;
@ -128,7 +128,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen
// There must be a delay of at least 20 ms after sending the command. // There must be a delay of at least 20 ms after sending the command.
// Delay for 70 ms here and release the SPI bus for that duration. // Delay for 70 ms here and release the SPI bus for that duration.
closeSpi(fileDescriptor, gpioId, &gpioIF, mutex); closeSpi(fileDescriptor, gpioId, &gpioIF, mutex);
usleep(RwDefinitions::SPI_REPLY_DELAY); usleep(rws::SPI_REPLY_DELAY);
result = openSpi(dev, O_RDWR, &gpioIF, gpioId, mutex, timeoutType, timeoutMs, fileDescriptor); result = openSpi(dev, O_RDWR, &gpioIF, gpioId, mutex, timeoutType, timeoutMs, fileDescriptor);
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
return result; return result;
@ -143,13 +143,13 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen
if (read(fileDescriptor, &byteRead, 1) != 1) { if (read(fileDescriptor, &byteRead, 1) != 1) {
sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl; sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl;
closeSpi(fileDescriptor, gpioId, &gpioIF, mutex); closeSpi(fileDescriptor, gpioId, &gpioIF, mutex);
return RwHandler::SPI_READ_FAILURE; return rws::SPI_READ_FAILURE;
} }
if (idx == 0) { if (idx == 0) {
if (byteRead != FLAG_BYTE) { if (byteRead != FLAG_BYTE) {
sif::error << "Invalid data, expected start marker" << std::endl; sif::error << "Invalid data, expected start marker" << std::endl;
closeSpi(fileDescriptor, gpioId, &gpioIF, mutex); closeSpi(fileDescriptor, gpioId, &gpioIF, mutex);
return RwHandler::NO_START_MARKER; return rws::NO_START_MARKER;
} }
} }
@ -160,7 +160,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen
if (idx == 9) { if (idx == 9) {
sif::error << "rwSpiCallback::spiCallback: Empty frame timeout" << std::endl; sif::error << "rwSpiCallback::spiCallback: Empty frame timeout" << std::endl;
closeSpi(fileDescriptor, gpioId, &gpioIF, mutex); closeSpi(fileDescriptor, gpioId, &gpioIF, mutex);
return RwHandler::NO_REPLY; return rws::NO_REPLY;
} }
} }
@ -175,7 +175,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen
byteRead = 0; byteRead = 0;
if (read(fileDescriptor, &byteRead, 1) != 1) { if (read(fileDescriptor, &byteRead, 1) != 1) {
sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl; sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl;
result = RwHandler::SPI_READ_FAILURE; result = rws::SPI_READ_FAILURE;
break; break;
} }
} }
@ -186,7 +186,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen
} else if (byteRead == 0x7D) { } else if (byteRead == 0x7D) {
if (read(fileDescriptor, &byteRead, 1) != 1) { if (read(fileDescriptor, &byteRead, 1) != 1) {
sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl; sif::error << "rwSpiCallback::spiCallback: Read failed" << std::endl;
result = RwHandler::SPI_READ_FAILURE; result = rws::SPI_READ_FAILURE;
break; break;
} }
if (byteRead == 0x5E) { if (byteRead == 0x5E) {
@ -200,7 +200,7 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen
} else { } else {
sif::error << "rwSpiCallback::spiCallback: Invalid substitute" << std::endl; sif::error << "rwSpiCallback::spiCallback: Invalid substitute" << std::endl;
closeSpi(fileDescriptor, gpioId, &gpioIF, mutex); closeSpi(fileDescriptor, gpioId, &gpioIF, mutex);
result = RwHandler::INVALID_SUBSTITUTE; result = rws::INVALID_SUBSTITUTE;
break; break;
} }
} else { } else {
@ -217,14 +217,14 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen
if (decodedFrameLen == replyBufferSize) { if (decodedFrameLen == replyBufferSize) {
if (read(fileDescriptor, &byteRead, 1) != 1) { if (read(fileDescriptor, &byteRead, 1) != 1) {
sif::error << "rwSpiCallback::spiCallback: Failed to read last byte" << std::endl; sif::error << "rwSpiCallback::spiCallback: Failed to read last byte" << std::endl;
result = RwHandler::SPI_READ_FAILURE; result = rws::SPI_READ_FAILURE;
break; break;
} }
if (byteRead != FLAG_BYTE) { if (byteRead != FLAG_BYTE) {
sif::error << "rwSpiCallback::spiCallback: Missing end sign " << static_cast<int>(FLAG_BYTE) sif::error << "rwSpiCallback::spiCallback: Missing end sign " << static_cast<int>(FLAG_BYTE)
<< std::endl; << std::endl;
decodedFrameLen--; decodedFrameLen--;
result = RwHandler::MISSING_END_SIGN; result = rws::MISSING_END_SIGN;
break; break;
} }
} }

View File

@ -1,6 +1,7 @@
#include "ObjectFactory.h" #include "ObjectFactory.h"
#include <fsfw/subsystem/Subsystem.h> #include <fsfw/subsystem/Subsystem.h>
#include <linux/devices/RwPollingTask.h>
#include <mission/system/objects/CamSwitcher.h> #include <mission/system/objects/CamSwitcher.h>
#include "OBSWConfig.h" #include "OBSWConfig.h"
@ -58,6 +59,7 @@
#include <mission/devices/ImtqHandler.h> #include <mission/devices/ImtqHandler.h>
#include <mission/devices/PcduHandler.h> #include <mission/devices/PcduHandler.h>
#include <mission/devices/SyrlinksHandler.h> #include <mission/devices/SyrlinksHandler.h>
#include <mission/devices/devicedefinitions/rwHelpers.h>
#include <sstream> #include <sstream>
@ -94,7 +96,6 @@
#include "mission/devices/devicedefinitions/GomspaceDefinitions.h" #include "mission/devices/devicedefinitions/GomspaceDefinitions.h"
#include "mission/devices/devicedefinitions/Max31865Definitions.h" #include "mission/devices/devicedefinitions/Max31865Definitions.h"
#include "mission/devices/devicedefinitions/RadSensorDefinitions.h" #include "mission/devices/devicedefinitions/RadSensorDefinitions.h"
#include "mission/devices/devicedefinitions/RwDefinitions.h"
#include "mission/devices/devicedefinitions/SyrlinksDefinitions.h" #include "mission/devices/devicedefinitions/SyrlinksDefinitions.h"
#include "mission/devices/devicedefinitions/payloadPcduDefinitions.h" #include "mission/devices/devicedefinitions/payloadPcduDefinitions.h"
#include "mission/system/objects/AcsBoardAssembly.h" #include "mission/system/objects/AcsBoardAssembly.h"
@ -150,9 +151,8 @@ void ObjectFactory::createTmpComponents() {
void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF,
SerialComIF** uartComIF, SpiComIF** spiMainComIF, SerialComIF** uartComIF, SpiComIF** spiMainComIF,
I2cComIF** i2cComIF, SpiComIF** spiRWComIF) { I2cComIF** i2cComIF) {
if (gpioComIF == nullptr or uartComIF == nullptr or spiMainComIF == nullptr or if (gpioComIF == nullptr or uartComIF == nullptr or spiMainComIF == nullptr) {
spiRWComIF == nullptr) {
sif::error << "ObjectFactory::createCommunicationInterfaces: Invalid passed ComIF pointer" sif::error << "ObjectFactory::createCommunicationInterfaces: Invalid passed ComIF pointer"
<< std::endl; << std::endl;
} }
@ -163,7 +163,7 @@ void ObjectFactory::createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF,
*i2cComIF = new I2cComIF(objects::I2C_COM_IF); *i2cComIF = new I2cComIF(objects::I2C_COM_IF);
*uartComIF = new SerialComIF(objects::UART_COM_IF); *uartComIF = new SerialComIF(objects::UART_COM_IF);
*spiMainComIF = new SpiComIF(objects::SPI_MAIN_COM_IF, q7s::SPI_DEFAULT_DEV, **gpioComIF); *spiMainComIF = new SpiComIF(objects::SPI_MAIN_COM_IF, q7s::SPI_DEFAULT_DEV, **gpioComIF);
*spiRWComIF = new SpiComIF(objects::SPI_RW_COM_IF, q7s::SPI_RW_DEV, **gpioComIF); //*spiRWComIF = new SpiComIF(objects::SPI_RW_COM_IF, q7s::SPI_RW_DEV, **gpioComIF);
} }
void ObjectFactory::createPcduComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF** pwrSwitcher) { void ObjectFactory::createPcduComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF** pwrSwitcher) {
@ -678,13 +678,12 @@ void ObjectFactory::createReactionWheelComponents(LinuxLibgpioIF* gpioComIF,
std::array<gpioId_t, 4> rwGpioIds = {gpioIds::EN_RW1, gpioIds::EN_RW2, gpioIds::EN_RW3, std::array<gpioId_t, 4> rwGpioIds = {gpioIds::EN_RW1, gpioIds::EN_RW2, gpioIds::EN_RW3,
gpioIds::EN_RW4}; gpioIds::EN_RW4};
std::array<DeviceHandlerBase*, 4> rws = {}; std::array<DeviceHandlerBase*, 4> rws = {};
new RwPollingTask(objects::RW_POLLING_TASK, q7s::SPI_RW_DEV, *gpioComIF);
for (uint8_t idx = 0; idx < rwCookies.size(); idx++) { for (uint8_t idx = 0; idx < rwCookies.size(); idx++) {
rwCookies[idx] = new SpiCookie(rwCookieParams[idx].first, rwCookieParams[idx].second, rwCookies[idx] = new RwCookie(idx, rwCookieParams[idx].first, rwCookieParams[idx].second,
RwDefinitions::MAX_REPLY_SIZE, spi::RW_MODE, spi::RW_SPEED, rws::MAX_REPLY_SIZE, spi::RW_MODE, spi::RW_SPEED);
&rwSpiCallback::spiCallback, nullptr); auto* rwHandler = new RwHandler(rwIds[idx], objects::RW_POLLING_TASK, rwCookies[idx], gpioComIF,
auto* rwHandler = new RwHandler(rwIds[idx], objects::SPI_RW_COM_IF, rwCookies[idx], gpioComIF, rwGpioIds[idx], idx);
rwGpioIds[idx]);
rwCookies[idx]->setCallbackArgs(rws[idx]);
#if OBSW_TEST_RW == 1 #if OBSW_TEST_RW == 1
rws[idx]->setStartUpImmediately(); rws[idx]->setStartUpImmediately();
#endif #endif

View File

@ -25,8 +25,7 @@ void setStatics();
void produce(void* args); void produce(void* args);
void createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, SerialComIF** uartComIF, void createCommunicationInterfaces(LinuxLibgpioIF** gpioComIF, SerialComIF** uartComIF,
SpiComIF** spiMainComIF, I2cComIF** i2cComIF, SpiComIF** spiMainComIF, I2cComIF** i2cComIF);
SpiComIF** spiRwComIF);
void createPcduComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF** pwrSwitcher); void createPcduComponents(LinuxLibgpioIF* gpioComIF, PowerSwitchIF** pwrSwitcher);
void createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF, void createPlPcduComponents(LinuxLibgpioIF* gpioComIF, SpiComIF* spiComIF,
PowerSwitchIF* pwrSwitcher, Stack5VHandler& stackHandler); PowerSwitchIF* pwrSwitcher, Stack5VHandler& stackHandler);

View File

@ -196,6 +196,15 @@ void scheduling::initTasks() {
} }
#endif /* OBSW_ADD_GPS_CTRL */ #endif /* OBSW_ADD_GPS_CTRL */
#if OBSW_ADD_RW == 1
PeriodicTaskIF* rwPolling = factory->createPeriodicTask(
"RW_POLLING_TASK", 70, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc);
result = rwPolling->addComponent(objects::RW_POLLING_TASK);
if (result != returnvalue::OK) {
scheduling::printAddObjectError("RW_POLLING_TASK", objects::RW_POLLING_TASK);
}
#endif
PeriodicTaskIF* acsSysTask = factory->createPeriodicTask( PeriodicTaskIF* acsSysTask = factory->createPeriodicTask(
"ACS_SYS_TASK", 55, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc); "ACS_SYS_TASK", 55, PeriodicTaskIF::MINIMUM_STACK_SIZE * 2, 0.4, missedDeadlineFunc);
static_cast<void>(acsSysTask); static_cast<void>(acsSysTask);
@ -355,6 +364,9 @@ void scheduling::initTasks() {
strHelperTask->startTask(); strHelperTask->startTask();
#endif /* OBSW_ADD_STAR_TRACKER == 1 */ #endif /* OBSW_ADD_STAR_TRACKER == 1 */
#if OBSW_ADD_RW == 1
rwPolling->startTask();
#endif
#if OBSW_ADD_GPS_CTRL == 1 #if OBSW_ADD_GPS_CTRL == 1
gpsTask->startTask(); gpsTask->startTask();
#endif #endif

View File

@ -26,8 +26,7 @@ void ObjectFactory::produce(void* args) {
SpiComIF* spiMainComIF = nullptr; SpiComIF* spiMainComIF = nullptr;
I2cComIF* i2cComIF = nullptr; I2cComIF* i2cComIF = nullptr;
PowerSwitchIF* pwrSwitcher = nullptr; PowerSwitchIF* pwrSwitcher = nullptr;
SpiComIF* spiRwComIF = nullptr; createCommunicationInterfaces(&gpioComIF, &uartComIF, &spiMainComIF, &i2cComIF);
createCommunicationInterfaces(&gpioComIF, &uartComIF, &spiMainComIF, &i2cComIF, &spiRwComIF);
/* Adding gpios for chip select decoding to the gpioComIf */ /* Adding gpios for chip select decoding to the gpioComIf */
q7s::gpioCallbacks::initSpiCsDecoder(gpioComIF); q7s::gpioCallbacks::initSpiCsDecoder(gpioComIF);
gpioCallbacks::disableAllDecoder(gpioComIF); gpioCallbacks::disableAllDecoder(gpioComIF);

View File

@ -74,16 +74,23 @@ int obsw::obsw() {
scheduling::initMission(); scheduling::initMission();
#if OBSW_COMMAND_SAFE_MODE_AT_STARTUP == 1
// Command the EIVE system to safe mode // Command the EIVE system to safe mode
auto sysQueueId = satsystem::EIVE_SYSTEM.getCommandQueue(); auto sysQueueId = satsystem::EIVE_SYSTEM.getCommandQueue();
CommandMessage msg; CommandMessage msg;
#if OBSW_COMMAND_SAFE_MODE_AT_STARTUP == 1
ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, 0); ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, 0);
ReturnValue_t result = ReturnValue_t result =
MessageQueueSenderIF::sendMessage(sysQueueId, &msg, MessageQueueIF::NO_QUEUE, false); MessageQueueSenderIF::sendMessage(sysQueueId, &msg, MessageQueueIF::NO_QUEUE, false);
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
sif::error << "Sending safe mode command to EIVE system failed" << std::endl; sif::error << "Sending safe mode command to EIVE system failed" << std::endl;
} }
#else
ModeMessage::setModeAnnounceMessage(msg, true);
ReturnValue_t result =
MessageQueueSenderIF::sendMessage(sysQueueId, &msg, MessageQueueIF::NO_QUEUE, false);
if (result != returnvalue::OK) {
sif::error << "Sending safe mode command to EIVE system failed" << std::endl;
}
#endif #endif
for (;;) { for (;;) {

View File

@ -57,14 +57,19 @@ static constexpr uint32_t MAX_STORED_CMDS_TCP = 150;
namespace acs { namespace acs {
static constexpr uint32_t SCHED_BLOCK_1_SENSORS_MS = 15; static constexpr uint32_t SCHED_BLOCK_1_SUS_READ_MS = 15;
static constexpr uint32_t SCHED_BLOCK_2_ACS_CTRL_MS = 40; static constexpr uint32_t SCHED_BLOCK_2_SENSOR_READ_MS = 30;
static constexpr uint32_t SCHED_BLOCK_3_ACTUATOR_MS = 45; static constexpr uint32_t SCHED_BLOCK_3_ACS_CTRL_MS = 45;
static constexpr uint32_t SCHED_BLOCK_4_ACTUATOR_MS = 50;
static constexpr uint32_t SCHED_BLOCK_5_RW_READ_MS = 300;
// 15 ms for FM // 15 ms for FM
static constexpr float SCHED_BLOCK_1_PERIOD = static_cast<float>(SCHED_BLOCK_1_SENSORS_MS) / 400.0; static constexpr float SCHED_BLOCK_1_PERIOD = static_cast<float>(SCHED_BLOCK_1_SUS_READ_MS) / 400.0;
static constexpr float SCHED_BLOCK_2_PERIOD = static_cast<float>(SCHED_BLOCK_2_ACS_CTRL_MS) / 400.0; static constexpr float SCHED_BLOCK_2_PERIOD =
static constexpr float SCHED_BLOCK_3_PERIOD = static_cast<float>(SCHED_BLOCK_3_ACTUATOR_MS) / 400.0; static_cast<float>(SCHED_BLOCK_2_SENSOR_READ_MS) / 400.0;
static constexpr float SCHED_BLOCK_3_PERIOD = static_cast<float>(SCHED_BLOCK_3_ACS_CTRL_MS) / 400.0;
static constexpr float SCHED_BLOCK_4_PERIOD = static_cast<float>(SCHED_BLOCK_4_ACTUATOR_MS) / 400.0;
static constexpr float SCHED_BLOCK_5_PERIOD = static_cast<float>(SCHED_BLOCK_5_RW_READ_MS) / 400.0;
} // namespace acs } // namespace acs

View File

@ -1,6 +1,6 @@
#include "RwDummy.h" #include "RwDummy.h"
#include <mission/devices/devicedefinitions/RwDefinitions.h> #include <mission/devices/devicedefinitions/rwHelpers.h>
RwDummy::RwDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie) RwDummy::RwDummy(object_id_t objectId, object_id_t comif, CookieIF *comCookie)
: DeviceHandlerBase(objectId, comif, comCookie) {} : DeviceHandlerBase(objectId, comif, comCookie) {}
@ -37,39 +37,39 @@ uint32_t RwDummy::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return
ReturnValue_t RwDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, ReturnValue_t RwDummy::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) { LocalDataPoolManager &poolManager) {
localDataPoolMap.emplace(RwDefinitions::TEMPERATURE_C, new PoolEntry<int32_t>({0})); localDataPoolMap.emplace(rws::TEMPERATURE_C, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::CURR_SPEED, new PoolEntry<int32_t>({0})); localDataPoolMap.emplace(rws::CURR_SPEED, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::REFERENCE_SPEED, new PoolEntry<int32_t>({0})); localDataPoolMap.emplace(rws::REFERENCE_SPEED, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::STATE, new PoolEntry<uint8_t>({0})); localDataPoolMap.emplace(rws::STATE, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::CLC_MODE, new PoolEntry<uint8_t>({0})); localDataPoolMap.emplace(rws::CLC_MODE, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::LAST_RESET_STATUS, new PoolEntry<uint8_t>({0})); localDataPoolMap.emplace(rws::LAST_RESET_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::CURRRENT_RESET_STATUS, new PoolEntry<uint8_t>({0})); localDataPoolMap.emplace(rws::CURRRENT_RESET_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::TM_LAST_RESET_STATUS, new PoolEntry<uint8_t>({0})); localDataPoolMap.emplace(rws::TM_LAST_RESET_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::TM_MCU_TEMPERATURE, new PoolEntry<int32_t>({0})); localDataPoolMap.emplace(rws::TM_MCU_TEMPERATURE, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::PRESSURE_SENSOR_TEMPERATURE, new PoolEntry<float>({0})); localDataPoolMap.emplace(rws::PRESSURE_SENSOR_TEMPERATURE, new PoolEntry<float>({0}));
localDataPoolMap.emplace(RwDefinitions::PRESSURE, new PoolEntry<float>({0})); localDataPoolMap.emplace(rws::PRESSURE, new PoolEntry<float>({0}));
localDataPoolMap.emplace(RwDefinitions::TM_RW_STATE, new PoolEntry<uint8_t>({0})); localDataPoolMap.emplace(rws::TM_RW_STATE, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::TM_CLC_MODE, new PoolEntry<uint8_t>({0})); localDataPoolMap.emplace(rws::TM_CLC_MODE, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::TM_RW_CURR_SPEED, new PoolEntry<int32_t>({0})); localDataPoolMap.emplace(rws::TM_RW_CURR_SPEED, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::TM_RW_REF_SPEED, new PoolEntry<int32_t>({0})); localDataPoolMap.emplace(rws::TM_RW_REF_SPEED, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::INVALID_CRC_PACKETS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::INVALID_CRC_PACKETS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::INVALID_LEN_PACKETS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::INVALID_LEN_PACKETS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::INVALID_CMD_PACKETS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::INVALID_CMD_PACKETS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::EXECUTED_REPLIES, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::EXECUTED_REPLIES, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::COMMAND_REPLIES, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::COMMAND_REPLIES, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_BYTES_WRITTEN, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_BYTES_WRITTEN, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_BYTES_READ, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_BYTES_READ, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_PARITY_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_PARITY_ERRORS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_NOISE_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_NOISE_ERRORS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_FRAME_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_FRAME_ERRORS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_REG_OVERRUN_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_REG_OVERRUN_ERRORS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_TOTAL_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_TOTAL_ERRORS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::SPI_BYTES_WRITTEN, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::SPI_BYTES_WRITTEN, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::SPI_BYTES_READ, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::SPI_BYTES_READ, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::SPI_REG_OVERRUN_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::SPI_REG_OVERRUN_ERRORS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::SPI_TOTAL_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::SPI_TOTAL_ERRORS, new PoolEntry<uint32_t>({0}));
return returnvalue::OK; return returnvalue::OK;
} }

2
fsfw

@ -1 +1 @@
Subproject commit 70b785984c8af916fc96d8fc9e2627c20ee85461 Subproject commit a6d707a7db589136ac2bd917cd8b3a3e2c16a0e4

View File

@ -121,8 +121,8 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path
11706;0x2dba;SELF_TEST_MTM_RANGE_FAILURE;LOW;Get self test result returns failure that MTM values were outside of the expected range. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;mission/devices/ImtqHandler.h 11706;0x2dba;SELF_TEST_MTM_RANGE_FAILURE;LOW;Get self test result returns failure that MTM values were outside of the expected range. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;mission/devices/ImtqHandler.h
11707;0x2dbb;SELF_TEST_COIL_CURRENT_FAILURE;LOW;Get self test result returns failure indicating that the coil current was outside of the expected range P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;mission/devices/ImtqHandler.h 11707;0x2dbb;SELF_TEST_COIL_CURRENT_FAILURE;LOW;Get self test result returns failure indicating that the coil current was outside of the expected range P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;mission/devices/ImtqHandler.h
11708;0x2dbc;INVALID_ERROR_BYTE;LOW;Received invalid error byte. This indicates an error of the communication link between IMTQ and OBC.;mission/devices/ImtqHandler.h 11708;0x2dbc;INVALID_ERROR_BYTE;LOW;Received invalid error byte. This indicates an error of the communication link between IMTQ and OBC.;mission/devices/ImtqHandler.h
11801;0x2e19;ERROR_STATE;HIGH;Reaction wheel signals an error state;mission/devices/devicedefinitions/RwDefinitions.h 11801;0x2e19;ERROR_STATE;HIGH;Reaction wheel signals an error state;mission/devices/devicedefinitions/rwHelpers.h
11802;0x2e1a;RESET_OCCURED;LOW;;mission/devices/devicedefinitions/RwDefinitions.h 11802;0x2e1a;RESET_OCCURED;LOW;;mission/devices/devicedefinitions/rwHelpers.h
11901;0x2e7d;BOOTING_FIRMWARE_FAILED;LOW;Failed to boot firmware;linux/devices/startracker/StarTrackerHandler.h 11901;0x2e7d;BOOTING_FIRMWARE_FAILED;LOW;Failed to boot firmware;linux/devices/startracker/StarTrackerHandler.h
11902;0x2e7e;BOOTING_BOOTLOADER_FAILED;LOW;Failed to boot star tracker into bootloader mode;linux/devices/startracker/StarTrackerHandler.h 11902;0x2e7e;BOOTING_BOOTLOADER_FAILED;LOW;Failed to boot star tracker into bootloader mode;linux/devices/startracker/StarTrackerHandler.h
12001;0x2ee1;SUPV_MEMORY_READ_RPT_CRC_FAILURE;LOW;PLOC supervisor crc failure in telemetry packet;linux/devices/ploc/PlocSupervisorHandler.h 12001;0x2ee1;SUPV_MEMORY_READ_RPT_CRC_FAILURE;LOW;PLOC supervisor crc failure in telemetry packet;linux/devices/ploc/PlocSupervisorHandler.h

1 Event ID (dec) Event ID (hex) Name Severity Description File Path
121 11703 11706 0x2db7 0x2dba SELF_TEST_ADC_FAILURE SELF_TEST_MTM_RANGE_FAILURE LOW Get self test result returns failure in measurement of current and temperature. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA Get self test result returns failure that MTM values were outside of the expected range. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA mission/devices/ImtqHandler.h
122 11704 11707 0x2db8 0x2dbb SELF_TEST_PWM_FAILURE SELF_TEST_COIL_CURRENT_FAILURE LOW Get self test result returns PWM failure which concerns the coil actuation. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA Get self test result returns failure indicating that the coil current was outside of the expected range P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA mission/devices/ImtqHandler.h
123 11705 11708 0x2db9 0x2dbc SELF_TEST_TC_FAILURE INVALID_ERROR_BYTE LOW Get self test result returns TC failure (system failure) P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA Received invalid error byte. This indicates an error of the communication link between IMTQ and OBC. mission/devices/ImtqHandler.h
124 11706 11801 0x2dba 0x2e19 SELF_TEST_MTM_RANGE_FAILURE ERROR_STATE LOW HIGH Get self test result returns failure that MTM values were outside of the expected range. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA Reaction wheel signals an error state mission/devices/ImtqHandler.h mission/devices/devicedefinitions/rwHelpers.h
125 11707 11802 0x2dbb 0x2e1a SELF_TEST_COIL_CURRENT_FAILURE RESET_OCCURED LOW Get self test result returns failure indicating that the coil current was outside of the expected range P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA mission/devices/ImtqHandler.h mission/devices/devicedefinitions/rwHelpers.h
126 11708 11901 0x2dbc 0x2e7d INVALID_ERROR_BYTE BOOTING_FIRMWARE_FAILED LOW Received invalid error byte. This indicates an error of the communication link between IMTQ and OBC. Failed to boot firmware mission/devices/ImtqHandler.h linux/devices/startracker/StarTrackerHandler.h
127 11801 11902 0x2e19 0x2e7e ERROR_STATE BOOTING_BOOTLOADER_FAILED HIGH LOW Reaction wheel signals an error state Failed to boot star tracker into bootloader mode mission/devices/devicedefinitions/rwHelpers.h linux/devices/startracker/StarTrackerHandler.h
128 11802 12001 0x2e1a 0x2ee1 RESET_OCCURED SUPV_MEMORY_READ_RPT_CRC_FAILURE LOW No description PLOC supervisor crc failure in telemetry packet mission/devices/devicedefinitions/rwHelpers.h linux/devices/ploc/PlocSupervisorHandler.h

View File

@ -1,38 +1,29 @@
Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x0000;OK;System-wide code for ok.;0;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h 0x0000;OK;System-wide code for ok.;0;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h
0x0001;Failed;Unspecified system-wide code for failed.;1;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h 0x0001;Failed;Unspecified system-wide code for failed.;1;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h
0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h 0x63a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NVMParameterBase.h
0x5d00;GOMS_PacketTooLong;;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x6300;NVMB_Busy;;0;NVM_PARAM_BASE;mission/system/objects/Stack5VHandler.h
0x5d01;GOMS_InvalidTableId;;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x52b0;RWHA_SpiWriteFailure;;176;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.h
0x5d02;GOMS_InvalidAddress;;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x52b1;RWHA_SpiReadFailure;Used by the spi send function to tell a failing read call;177;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.h
0x5d03;GOMS_InvalidParamSize;;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.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/devicedefinitions/rwHelpers.h
0x5d04;GOMS_InvalidPayloadSize;;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x52b3;RWHA_InvalidSubstitute;Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination;179;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.h
0x5d05;GOMS_UnknownReplyId;;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x52b4;RWHA_MissingEndSign;HDLC decoding mechanism never receives the end sign 0x7E;180;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.h
0x52b0;RWHA_SpiWriteFailure;;176;RW_HANDLER;mission/devices/RwHandler.h 0x52b5;RWHA_NoReply;Reaction wheel only responds with empty frames.;181;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.h
0x52b1;RWHA_SpiReadFailure;Used by the spi send function to tell a failing read call;177;RW_HANDLER;mission/devices/RwHandler.h 0x52b6;RWHA_NoStartMarker;Expected a start marker as first byte;182;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.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 0x52b7;RWHA_SpiReadTimeout;Timeout when reading reply;183;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.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
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 0x58a0;SUSS_ErrorUnlockMutex;;160;SUS_HANDLER;mission/devices/SusHandler.h
0x58a1;SUSS_ErrorLockMutex;;161;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 0x66a0;SADPL_CommandNotSupported;;160;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
0x51a1;IMTQ_ParameterMissing;;161;IMTQ_HANDLER;mission/devices/ImtqHandler.h 0x66a1;SADPL_DeploymentAlreadyExecuting;;161;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
0x51a2;IMTQ_ParameterInvalid;;162;IMTQ_HANDLER;mission/devices/ImtqHandler.h 0x66a2;SADPL_MainSwitchTimeoutFailure;;162;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
0x51a3;IMTQ_CcUnavailable;;163;IMTQ_HANDLER;mission/devices/ImtqHandler.h 0x66a3;SADPL_SwitchingDeplSa1Failed;;163;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
0x51a4;IMTQ_InternalProcessingError;;164;IMTQ_HANDLER;mission/devices/ImtqHandler.h 0x66a4;SADPL_SwitchingDeplSa2Failed;;164;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
0x51a5;IMTQ_RejectedWithoutReason;;165;IMTQ_HANDLER;mission/devices/ImtqHandler.h 0x51a0;IMTQ_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;IMTQ_HANDLER;mission/devices/RwHandler.h
0x51a1;IMTQ_InvalidRampTime;Action Message with invalid ramp time was received.;161;IMTQ_HANDLER;mission/devices/RwHandler.h
0x51a2;IMTQ_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;IMTQ_HANDLER;mission/devices/RwHandler.h
0x51a3;IMTQ_ExecutionFailed;Command execution failed;163;IMTQ_HANDLER;mission/devices/RwHandler.h
0x51a4;IMTQ_CrcError;Reaction wheel reply has invalid crc;164;IMTQ_HANDLER;mission/devices/RwHandler.h
0x51a5;IMTQ_ValueNotRead;;165;IMTQ_HANDLER;mission/devices/RwHandler.h
0x51a6;IMTQ_CmdErrUnknown;;166;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 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/SyrlinksHandler.h 0x50a0;SYRLINKS_CrcFailure;;160;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h
@ -44,137 +35,123 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x50a6;SYRLINKS_BadCrcAck;;166;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a6;SYRLINKS_BadCrcAck;;166;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h
0x50a7;SYRLINKS_ReplyWrongSize;;167;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a7;SYRLINKS_ReplyWrongSize;;167;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h
0x50a8;SYRLINKS_MissingStartFrameCharacter;;168;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a8;SYRLINKS_MissingStartFrameCharacter;;168;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h
0x66a0;SADPL_CommandNotSupported;;160;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h 0x5d00;GOMS_PacketTooLong;;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x66a1;SADPL_DeploymentAlreadyExecuting;;161;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h 0x5d01;GOMS_InvalidTableId;;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x66a2;SADPL_MainSwitchTimeoutFailure;;162;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h 0x5d02;GOMS_InvalidAddress;;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x66a3;SADPL_SwitchingDeplSa1Failed;;163;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h 0x5d03;GOMS_InvalidParamSize;;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x66a4;SADPL_SwitchingDeplSa2Failed;;164;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h 0x5d04;GOMS_InvalidPayloadSize;;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x6600;SADPL_Busy;;0;SA_DEPL_HANDLER;mission/system/objects/Stack5VHandler.h 0x5d05;GOMS_UnknownReplyId;;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x6b01;ACSPTG_PtgctrlMekfInputInvalid;;1;ACS_PTG;mission/controller/acs/control/PtgCtrl.h 0x4fa1;HEATER_CommandNotSupported;;161;HEATER_HANDLER;mission/devices/HeaterHandler.h
0x4fa2;HEATER_InitFailed;;162;HEATER_HANDLER;mission/devices/HeaterHandler.h
0x4fa3;HEATER_InvalidSwitchNr;;163;HEATER_HANDLER;mission/devices/HeaterHandler.h
0x4fa4;HEATER_MainSwitchSetTimeout;;164;HEATER_HANDLER;mission/devices/HeaterHandler.h
0x4fa5;HEATER_CommandAlreadyWaiting;;165;HEATER_HANDLER;mission/devices/HeaterHandler.h
0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h
0x6a01;ACSSAF_SafectrlMekfInputInvalid;;1;ACS_SAFE;mission/controller/acs/control/SafeCtrl.h 0x6a01;ACSSAF_SafectrlMekfInputInvalid;;1;ACS_SAFE;mission/controller/acs/control/SafeCtrl.h
0x6b01;ACSPTG_PtgctrlMekfInputInvalid;;1;ACS_PTG;mission/controller/acs/control/PtgCtrl.h
0x6c01;ACSDTB_DetumbleNoSensordata;;1;ACS_DETUMBLE;mission/controller/acs/control/Detumble.h 0x6c01;ACSDTB_DetumbleNoSensordata;;1;ACS_DETUMBLE;mission/controller/acs/control/Detumble.h
0x6901;ACSKAL_KalmanNoGyrMeas;;1;ACS_KALMAN;mission/controller/acs/MultiplicativeKalmanFilter.h 0x6901;ACSKAL_KalmanNoGyrMeas;;1;ACS_KALMAN;mission/controller/acs/MultiplicativeKalmanFilter.h
0x6902;ACSKAL_KalmanNoModel;;2;ACS_KALMAN;mission/controller/acs/MultiplicativeKalmanFilter.h 0x6902;ACSKAL_KalmanNoModel;;2;ACS_KALMAN;mission/controller/acs/MultiplicativeKalmanFilter.h
0x6903;ACSKAL_KalmanInversionFailed;;3;ACS_KALMAN;mission/controller/acs/MultiplicativeKalmanFilter.h 0x6903;ACSKAL_KalmanInversionFailed;;3;ACS_KALMAN;mission/controller/acs/MultiplicativeKalmanFilter.h
0x63a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NVMParameterBase.h 0x4500;HSPI_OpeningFileFailed;;0;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
0x2c01;CCS_BcIsSetVrCommand;;1;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4501;HSPI_FullDuplexTransferFailed;;1;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
0x2c02;CCS_BcIsUnlockCommand;;2;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4502;HSPI_HalfDuplexTransferFailed;;2;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
0x2cb0;CCS_BcIllegalCommand;;176;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4801;HGIO_UnknownGpioId;;1;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2cb1;CCS_BoardReadingNotFinished;;177;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4802;HGIO_DriveGpioFailure;;2;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2cf0;CCS_NsPositiveW;;240;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4803;HGIO_GpioTypeFailure;;3;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2cf1;CCS_NsNegativeW;;241;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4804;HGIO_GpioInvalidInstance;;4;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2cf2;CCS_NsLockout;;242;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4805;HGIO_GpioDuplicateDetected;;5;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2cf3;CCS_FarmInLockout;;243;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4806;HGIO_GpioInitFailed;;6;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2cf4;CCS_FarmInWait;;244;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4807;HGIO_GpioGetValueFailed;;7;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2ce0;CCS_WrongSymbol;;224;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4601;HURT_UartReadFailure;;1;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
0x2ce1;CCS_DoubleStart;;225;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4602;HURT_UartReadSizeMissmatch;;2;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
0x2ce2;CCS_StartSymbolMissed;;226;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4603;HURT_UartRxBufferTooSmall;;3;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
0x2ce3;CCS_EndWithoutStart;;227;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4400;UXOS_ExecutionFinished;Execution of the current command has finished;0;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
0x2ce4;CCS_TooLarge;;228;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.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
0x2ce5;CCS_TooShort;;229;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4402;UXOS_BytesRead;Some bytes have been read from the executing process;2;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
0x2ce6;CCS_WrongTfVersion;;230;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4403;UXOS_CommandError;Command execution failed;3;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
0x2ce7;CCS_WrongSpacecraftId;;231;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4404;UXOS_NoCommandLoadedOrPending;;4;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
0x2ce8;CCS_NoValidFrameType;;232;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4406;UXOS_PcloseCallError;;6;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
0x2ce9;CCS_CrcFailed;;233;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x2801;SM_DataTooLarge;;1;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2cea;CCS_VcNotFound;;234;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x2802;SM_DataStorageFull;;2;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2ceb;CCS_ForwardingFailed;;235;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x2803;SM_IllegalStorageId;;3;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2cec;CCS_ContentTooLarge;;236;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x2804;SM_DataDoesNotExist;;4;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2ced;CCS_ResidualData;;237;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x2805;SM_IllegalAddress;;5;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2cee;CCS_DataCorrupted;;238;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x2806;SM_PoolTooLarge;;6;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2cef;CCS_IllegalSegmentationFlag;;239;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x0601;PP_DoItMyself;;1;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2cd0;CCS_IllegalFlagCombination;;208;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x0602;PP_PointsToVariable;;2;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2cd1;CCS_ShorterThanHeader;;209;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x0603;PP_PointsToMemory;;3;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2cd2;CCS_TooShortBlockedPacket;;210;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x0604;PP_ActivityCompleted;;4;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2cd3;CCS_TooShortMapExtraction;;211;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x0605;PP_PointsToVectorUint8;;5;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x3b00;SPH_ConnBroken;;0;SEMAPHORE_IF;fsfw/src/fsfw/osal/common/TcpTmTcServer.h 0x0606;PP_PointsToVectorUint16;;6;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a01;IEC_NoConfigurationTable;;1;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x0607;PP_PointsToVectorUint32;;7;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a02;IEC_NoCpuTable;;2;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x0608;PP_PointsToVectorFloat;;8;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a03;IEC_InvalidWorkspaceAddress;;3;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x06a0;PP_DumpNotSupported;;160;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a04;IEC_TooLittleWorkspace;;4;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x06e0;PP_InvalidSize;;224;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a05;IEC_WorkspaceAllocation;;5;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x06e1;PP_InvalidAddress;;225;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a06;IEC_InterruptStackTooSmall;;6;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x06e2;PP_InvalidContent;;226;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a07;IEC_ThreadExitted;;7;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x06e3;PP_UnalignedAccess;;227;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a08;IEC_InconsistentMpInformation;;8;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x06e4;PP_WriteProtected;;228;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a09;IEC_InvalidNode;;9;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x13e0;MH_UnknownCmd;;224;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h
0x2a0a;IEC_NoMpci;;10;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x13e1;MH_InvalidAddress;;225;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h
0x2a0b;IEC_BadPacket;;11;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x13e2;MH_InvalidSize;;226;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h
0x2a0c;IEC_OutOfPackets;;12;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x13e3;MH_StateMismatch;;227;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h
0x2a0d;IEC_OutOfGlobalObjects;;13;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38a1;SGP4_InvalidEccentricity;;161;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a0e;IEC_OutOfProxies;;14;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38a2;SGP4_InvalidMeanMotion;;162;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a0f;IEC_InvalidGlobalId;;15;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38a3;SGP4_InvalidPerturbationElements;;163;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a10;IEC_BadStackHook;;16;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38a4;SGP4_InvalidSemiLatusRectum;;164;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a11;IEC_BadAttributes;;17;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38a5;SGP4_InvalidEpochElements;;165;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a12;IEC_ImplementationKeyCreateInconsistency;;18;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38a6;SGP4_SatelliteHasDecayed;;166;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a13;IEC_ImplementationBlockingOperationCancel;;19;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38b1;SGP4_TleTooOld;;177;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a14;IEC_MutexObtainFromBadState;;20;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38b2;SGP4_TleNotInitialized;;178;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a15;IEC_UnlimitedAndMaximumIs0;;21;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.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 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 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 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 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 0x0c02;MS_InvalidEntry;;2;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
0x2e02;HPA_InvalidDomainId;;2;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h 0x0c03;MS_TooManyElements;;3;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
0x2e03;HPA_InvalidValue;;3;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h 0x0c04;MS_CantStoreEmpty;;4;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
0x2e05;HPA_ReadOnly;;5;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h 0x0b01;SB_ChildNotFound;;1;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x2d01;PAW_UnknownDatatype;;1;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0b02;SB_ChildInfoUpdated;;2;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x2d02;PAW_DatatypeMissmatch;;2;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0b03;SB_ChildDoesntHaveModes;;3;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x2d03;PAW_Readonly;;3;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0b04;SB_CouldNotInsertChild;;4;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x2d04;PAW_TooBig;;4;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0b05;SB_TableContainsInvalidObjectId;;5;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x2d05;PAW_SourceNotSet;;5;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0d01;SS_SequenceAlreadyExists;;1;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x2d06;PAW_OutOfBounds;;6;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0d02;SS_TableAlreadyExists;;2;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x2d07;PAW_NotSet;;7;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0d03;SS_TableDoesNotExist;;3;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x2d08;PAW_ColumnOrRowsZero;;8;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0d04;SS_TableOrSequenceLengthInvalid;;4;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x3201;CF_ObjectHasNoFunctions;;1;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h 0x0d05;SS_SequenceDoesNotExist;;5;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x3202;CF_AlreadyCommanding;;2;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h 0x0d06;SS_TableContainsInvalidObjectId;;6;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x3301;HF_IsBusy;;1;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h 0x0d07;SS_FallbackSequenceDoesNotExist;;7;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x3302;HF_InvalidParameters;;2;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h 0x0d08;SS_NoTargetTable;;8;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x3303;HF_ExecutionFinished;;3;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h 0x0d09;SS_SequenceOrTableTooLong;;9;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x3304;HF_InvalidActionId;;4;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h 0x0d0b;SS_IsFallbackSequence;;11;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0201;OM_InsertionFailed;;1;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h 0x0d0c;SS_AccessDenied;;12;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0202;OM_NotFound;;2;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h 0x0d0e;SS_TableInUse;;14;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0203;OM_ChildInitFailed;;3;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h 0x0da1;SS_TargetTableNotReached;;161;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0204;OM_InternalErrReporterUninit;;4;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h 0x0da2;SS_TableCheckFailed;;162;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x2600;FDI_YourFault;;0;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h 0x2501;EV_ListenerNotFound;;1;EVENT_MANAGER_IF;fsfw/src/fsfw/events/EventManagerIF.h
0x2601;FDI_MyFault;;1;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h
0x2602;FDI_ConfirmLater;;2;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h
0x2201;TMF_Busy;;1;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2202;TMF_LastPacketFound;;2;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2203;TMF_StopFetch;;3;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2204;TMF_Timeout;;4;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2205;TMF_TmChannelFull;;5;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2206;TMF_NotStored;;6;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2207;TMF_AllDeleted;;7;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2208;TMF_InvalidData;;8;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2209;TMF_NotReady;;9;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2101;TMB_Busy;;1;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2102;TMB_Full;;2;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2103;TMB_Empty;;3;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2104;TMB_NullRequested;;4;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2105;TMB_TooLarge;;5;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2106;TMB_NotReady;;6;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2107;TMB_DumpError;;7;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2108;TMB_CrcError;;8;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2109;TMB_Timeout;;9;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210a;TMB_IdlePacketFound;;10;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210b;TMB_TelecommandFound;;11;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210c;TMB_NoPusATm;;12;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210d;TMB_TooSmall;;13;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210e;TMB_BlockNotFound;;14;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210f;TMB_InvalidRequest;;15;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x1c01;TCD_PacketLost;;1;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1c02;TCD_DestinationNotFound;;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1c03;TCD_ServiceIdAlreadyExists;;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1b00;TCC_NoDestinationFound;;0;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b01;TCC_InvalidCcsdsVersion;;1;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b02;TCC_InvalidApid;;2;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b03;TCC_InvalidPacketType;;3;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b04;TCC_InvalidSecHeaderField;;4;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b05;TCC_IncorrectPrimaryHeader;;5;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b07;TCC_IncompletePacket;;7;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b08;TCC_InvalidPusVersion;;8;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b09;TCC_IncorrectChecksum;;9;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b0a;TCC_IllegalPacketSubtype;;10;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b0b;TCC_IncorrectSecondaryHeader;;11;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x04e1;RMP_CommandNoDescriptorsAvailable;;225;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x04e1;RMP_CommandNoDescriptorsAvailable;;225;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h
0x04e2;RMP_CommandBufferFull;;226;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 0x04e3;RMP_CommandChannelOutOfRange;;227;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h
@ -215,95 +192,9 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x040a;RMP_ReplyCommandNotImplementedOrNotAuthorised;;10;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x040a;RMP_ReplyCommandNotImplementedOrNotAuthorised;;10;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h
0x040b;RMP_ReplyRmwDataLengthError;;11;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 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 0x1401;SE_BufferTooShort;;1;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h
0x2802;SM_DataStorageFull;;2;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h 0x1402;SE_StreamTooShort;;2;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h
0x2803;SM_IllegalStorageId;;3;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h 0x1403;SE_TooManyElements;;3;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h
0x2804;SM_DataDoesNotExist;;4;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2805;SM_IllegalAddress;;5;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2806;SM_PoolTooLarge;;6;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x38a1;SGP4_InvalidEccentricity;;161;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38a2;SGP4_InvalidMeanMotion;;162;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38a3;SGP4_InvalidPerturbationElements;;163;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38a4;SGP4_InvalidSemiLatusRectum;;164;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38a5;SGP4_InvalidEpochElements;;165;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38a6;SGP4_SatelliteHasDecayed;;166;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38b1;SGP4_TleTooOld;;177;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38b2;SGP4_TleNotInitialized;;178;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2401;MT_NoPacketFound;;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h
0x2402;MT_PossiblePacketLoss;;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h
0x2403;MT_NoMatch;;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x2404;MT_Full;;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x2405;MT_NewNodeCreated;;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x3f01;DLEE_StreamTooShort;;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h
0x3f02;DLEE_DecodingError;;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h
0x2f01;ASC_TooLongForTargetType;;1;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x2f02;ASC_InvalidCharacters;;2;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x2f03;ASC_BufferTooSmall;;3;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x0f01;CM_UnknownCommand;;1;COMMAND_MESSAGE;fsfw/src/fsfw/ipc/CommandMessageIF.h
0x3a01;MQI_Empty;;1;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h
0x3a02;MQI_Full;No space left for more messages;2;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h
0x3a03;MQI_NoReplyPartner;Returned if a reply method was called without partner;3;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h
0x3a04;MQI_DestinationInvalid;Returned if the target destination is invalid.;4;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h
0x3901;MUX_NotEnoughResources;;1;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3902;MUX_InsufficientMemory;;2;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3903;MUX_NoPrivilege;;3;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3904;MUX_WrongAttributeSetting;;4;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3905;MUX_MutexAlreadyLocked;;5;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3906;MUX_MutexNotFound;;6;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3907;MUX_MutexMaxLocks;;7;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3908;MUX_CurrThreadAlreadyOwnsMutex;;8;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3909;MUX_CurrThreadDoesNotOwnMutex;;9;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x390a;MUX_MutexTimeout;;10;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x390b;MUX_MutexInvalidId;;11;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x390c;MUX_MutexDestroyedWhileWaiting;;12;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3b01;SPH_SemaphoreTimeout;;1;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h
0x3b02;SPH_SemaphoreNotOwned;;2;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h
0x3b03;SPH_SemaphoreInvalid;;3;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h
0x1e00;PUS_InvalidPusVersion;;0;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h
0x1e01;PUS_InvalidCrc16;;1;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h
0x3601;CFDP_InvalidTlvType;;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3602;CFDP_InvalidDirectiveField;;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3603;CFDP_InvalidPduDatafieldLen;;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3604;CFDP_InvalidAckDirectiveFields;;4;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3605;CFDP_MetadataCantParseOptions;;5;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3606;CFDP_NakCantParseOptions;;6;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3607;CFDP_FinishedCantParseFsResponses;;7;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3608;CFDP_FilestoreRequiresSecondFile;;8;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3609;CFDP_FilestoreResponseCantParseFsMessage;;9;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x360a;CFDP_InvalidPduFormat;;10;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x2901;TC_InvalidTargetState;;1;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h
0x29f1;TC_AboveOperationalLimit;;241;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h
0x29f2;TC_BelowOperationalLimit;;242;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h
0x0c02;MS_InvalidEntry;;2;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
0x0c03;MS_TooManyElements;;3;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
0x0c04;MS_CantStoreEmpty;;4;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
0x0d01;SS_SequenceAlreadyExists;;1;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d02;SS_TableAlreadyExists;;2;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d03;SS_TableDoesNotExist;;3;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d04;SS_TableOrSequenceLengthInvalid;;4;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d05;SS_SequenceDoesNotExist;;5;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d06;SS_TableContainsInvalidObjectId;;6;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d07;SS_FallbackSequenceDoesNotExist;;7;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d08;SS_NoTargetTable;;8;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d09;SS_SequenceOrTableTooLong;;9;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d0b;SS_IsFallbackSequence;;11;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d0c;SS_AccessDenied;;12;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d0e;SS_TableInUse;;14;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0da1;SS_TargetTableNotReached;;161;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0da2;SS_TableCheckFailed;;162;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0b01;SB_ChildNotFound;;1;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x0b02;SB_ChildInfoUpdated;;2;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x0b03;SB_ChildDoesntHaveModes;;3;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x0b04;SB_CouldNotInsertChild;;4;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x0b05;SB_TableContainsInvalidObjectId;;5;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x3e00;HKM_QueueOrDestinationInvalid;;0;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
0x3e01;HKM_WrongHkPacketType;;1;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
0x3e02;HKM_ReportingStatusUnchanged;;2;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
0x3e03;HKM_PeriodicHelperInvalid;;3;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
0x3e04;HKM_PoolobjectNotFound;;4;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
0x3e05;HKM_DatasetNotFound;;5;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
0x3c00;LPIF_PoolEntryNotFound;;0;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h
0x3c01;LPIF_PoolEntryTypeConflict;;1;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h
0x3da0;PVA_InvalidReadWriteMode;;160;POOL_VARIABLE_IF;fsfw/src/fsfw/datapool/PoolVariableIF.h 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 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 0x0801;DPS_InvalidParameterDefinition;;1;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h
@ -312,35 +203,20 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x0804;DPS_DataSetUninitialised;;4;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h 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 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 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 0x1c01;TCD_PacketLost;;1;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1001;TIM_NotEnoughInformationForTargetFormat;;1;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h 0x1c02;TCD_DestinationNotFound;;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1002;TIM_LengthMismatch;;2;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h 0x1c03;TCD_ServiceIdAlreadyExists;;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1003;TIM_InvalidTimeFormat;;3;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h 0x1b00;TCC_NoDestinationFound;;0;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1004;TIM_InvalidDayOfYear;;4;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h 0x1b01;TCC_InvalidCcsdsVersion;;1;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1005;TIM_TimeDoesNotFitFormat;;5;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h 0x1b02;TCC_InvalidApid;;2;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x3701;TSI_BadTimestamp;;1;TIME_STAMPER_IF;fsfw/src/fsfw/timemanager/TimeStampIF.h 0x1b03;TCC_InvalidPacketType;;3;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1d01;ATC_ActivityStarted;;1;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h 0x1b04;TCC_InvalidSecHeaderField;;4;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1d02;ATC_InvalidSubservice;;2;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h 0x1b05;TCC_IncorrectPrimaryHeader;;5;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1d03;ATC_IllegalApplicationData;;3;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h 0x1b07;TCC_IncompletePacket;;7;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1d04;ATC_SendTmFailed;;4;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h 0x1b08;TCC_InvalidPusVersion;;8;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1d05;ATC_Timeout;;5;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h 0x1b09;TCC_IncorrectChecksum;;9;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x4c00;SPPA_NoPacketFound;;0;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h 0x1b0a;TCC_IllegalPacketSubtype;;10;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x4c01;SPPA_SplitPacket;;1;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h 0x1b0b;TCC_IncorrectSecondaryHeader;;11;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x2001;CSB_ExecutionComplete;;1;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x2002;CSB_NoStepMessage;;2;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x2003;CSB_ObjectBusy;;3;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x2004;CSB_Busy;;4;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x2005;CSB_InvalidTc;;5;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x2006;CSB_InvalidObject;;6;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x2007;CSB_InvalidReply;;7;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x1801;FF_Full;;1;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h
0x1802;FF_Empty;;2;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h
0x1601;FMM_MapFull;;1;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h
0x1602;FMM_KeyDoesNotExist;;2;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h
0x2501;EV_ListenerNotFound;;1;EVENT_MANAGER_IF;fsfw/src/fsfw/events/EventManagerIF.h
0x1701;HHI_ObjectNotHealthy;;1;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h
0x1702;HHI_InvalidHealthState;;2;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h
0x1703;HHI_IsExternallyControlled;;3;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h
0x3001;POS_InPowerTransition;;1;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h 0x3001;POS_InPowerTransition;;1;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h
0x3002;POS_SwitchStateMismatch;;2;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 0x0501;PS_SwitchOn;;1;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h
@ -348,23 +224,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 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 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 0x0504;PS_FuseOff;;4;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h
0x4300;FILS_GenericFileError;;0;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x3b00;SPH_ConnBroken;;0;SEMAPHORE_IF;fsfw/src/fsfw/osal/common/TcpTmTcServer.h
0x4301;FILS_GenericDirError;;1;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a01;IEC_NoConfigurationTable;;1;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4302;FILS_FilesystemInactive;;2;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a02;IEC_NoCpuTable;;2;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4303;FILS_GenericRenameError;;3;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a03;IEC_InvalidWorkspaceAddress;;3;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4304;FILS_IsBusy;;4;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a04;IEC_TooLittleWorkspace;;4;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4305;FILS_InvalidParameters;;5;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a05;IEC_WorkspaceAllocation;;5;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x430a;FILS_FileDoesNotExist;;10;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a06;IEC_InterruptStackTooSmall;;6;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x430b;FILS_FileAlreadyExists;;11;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a07;IEC_ThreadExitted;;7;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x430c;FILS_NotAFile;;12;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a08;IEC_InconsistentMpInformation;;8;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x430d;FILS_FileLocked;;13;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a09;IEC_InvalidNode;;9;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x430e;FILS_PermissionDenied;;14;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a0a;IEC_NoMpci;;10;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4315;FILS_DirectoryDoesNotExist;;21;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a0b;IEC_BadPacket;;11;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4316;FILS_DirectoryAlreadyExists;;22;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a0c;IEC_OutOfPackets;;12;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4317;FILS_NotADirectory;;23;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a0d;IEC_OutOfGlobalObjects;;13;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4318;FILS_DirectoryNotEmpty;;24;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a0e;IEC_OutOfProxies;;14;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x431e;FILS_SequencePacketMissingWrite;;30;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a0f;IEC_InvalidGlobalId;;15;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x431f;FILS_SequencePacketMissingRead;;31;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.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 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 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 0x1a03;TRC_HighestValueOol;;3;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h
@ -383,36 +312,74 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x31e2;LIM_WrongPid;;226;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 0x31e3;LIM_WrongLimitId;;227;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h
0x31ee;LIM_MonitorNotFound;;238;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h 0x31ee;LIM_MonitorNotFound;;238;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h
0x3601;CFDP_InvalidTlvType;;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3602;CFDP_InvalidDirectiveField;;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3603;CFDP_InvalidPduDatafieldLen;;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3604;CFDP_InvalidAckDirectiveFields;;4;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3605;CFDP_MetadataCantParseOptions;;5;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3606;CFDP_NakCantParseOptions;;6;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3607;CFDP_FinishedCantParseFsResponses;;7;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3608;CFDP_FilestoreRequiresSecondFile;;8;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3609;CFDP_FilestoreResponseCantParseFsMessage;;9;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x360a;CFDP_InvalidPduFormat;;10;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x4300;FILS_GenericFileError;;0;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4301;FILS_GenericDirError;;1;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4302;FILS_FilesystemInactive;;2;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4303;FILS_GenericRenameError;;3;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4304;FILS_IsBusy;;4;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4305;FILS_InvalidParameters;;5;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x430a;FILS_FileDoesNotExist;;10;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x430b;FILS_FileAlreadyExists;;11;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x430c;FILS_NotAFile;;12;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x430d;FILS_FileLocked;;13;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x430e;FILS_PermissionDenied;;14;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4315;FILS_DirectoryDoesNotExist;;21;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4316;FILS_DirectoryAlreadyExists;;22;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4317;FILS_NotADirectory;;23;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4318;FILS_DirectoryNotEmpty;;24;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x431e;FILS_SequencePacketMissingWrite;;30;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x431f;FILS_SequencePacketMissingRead;;31;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x2c01;CCS_BcIsSetVrCommand;;1;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2c02;CCS_BcIsUnlockCommand;;2;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cb0;CCS_BcIllegalCommand;;176;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cb1;CCS_BoardReadingNotFinished;;177;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cf0;CCS_NsPositiveW;;240;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cf1;CCS_NsNegativeW;;241;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cf2;CCS_NsLockout;;242;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cf3;CCS_FarmInLockout;;243;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cf4;CCS_FarmInWait;;244;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce0;CCS_WrongSymbol;;224;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce1;CCS_DoubleStart;;225;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce2;CCS_StartSymbolMissed;;226;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce3;CCS_EndWithoutStart;;227;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce4;CCS_TooLarge;;228;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce5;CCS_TooShort;;229;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce6;CCS_WrongTfVersion;;230;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce7;CCS_WrongSpacecraftId;;231;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce8;CCS_NoValidFrameType;;232;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce9;CCS_CrcFailed;;233;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cea;CCS_VcNotFound;;234;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ceb;CCS_ForwardingFailed;;235;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cec;CCS_ContentTooLarge;;236;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ced;CCS_ResidualData;;237;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cee;CCS_DataCorrupted;;238;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cef;CCS_IllegalSegmentationFlag;;239;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cd0;CCS_IllegalFlagCombination;;208;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cd1;CCS_ShorterThanHeader;;209;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cd2;CCS_TooShortBlockedPacket;;210;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cd3;CCS_TooShortMapExtraction;;211;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x4201;PUS11_InvalidTypeTimeWindow;;1;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4201;PUS11_InvalidTypeTimeWindow;;1;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4202;PUS11_InvalidTimeWindow;;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4202;PUS11_InvalidTimeWindow;;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4203;PUS11_TimeshiftingNotPossible;;3;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4203;PUS11_TimeshiftingNotPossible;;3;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4204;PUS11_InvalidRelativeTime;;4;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4204;PUS11_InvalidRelativeTime;;4;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4205;PUS11_ContainedTcTooSmall;;5;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4205;PUS11_ContainedTcTooSmall;;5;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4206;PUS11_ContainedTcCrcMissmatch;;6;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4206;PUS11_ContainedTcCrcMissmatch;;6;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x0601;PP_DoItMyself;;1;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h 0x3401;DC_NoReplyReceived;;1;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
0x0602;PP_PointsToVariable;;2;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h 0x3402;DC_ProtocolError;;2;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
0x0603;PP_PointsToMemory;;3;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h 0x3403;DC_Nullpointer;;3;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
0x0604;PP_ActivityCompleted;;4;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h 0x3404;DC_InvalidCookieType;;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
0x0605;PP_PointsToVectorUint8;;5;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h 0x3405;DC_NotActive;;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
0x0606;PP_PointsToVectorUint16;;6;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h 0x3406;DC_TooMuchData;;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.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 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 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 0x03b1;DHB_IgnoreReplyData;;177;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
@ -422,12 +389,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 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 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 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 0x1201;AB_NeedSecondStep;;1;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x3402;DC_ProtocolError;;2;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h 0x1202;AB_NeedToReconfigure;;2;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x3403;DC_Nullpointer;;3;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h 0x1203;AB_ModeFallback;;3;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x3404;DC_InvalidCookieType;;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h 0x1204;AB_ChildNotCommandable;;4;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x3405;DC_NotActive;;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h 0x1205;AB_NeedToChangeHealth;;5;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x3406;DC_TooMuchData;;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.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 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 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 0x27a2;DHI_CommandAlreadySent;;162;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
@ -449,25 +416,54 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x27c3;DHI_DeviceReplyInvalid;;195;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 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 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 0x2401;MT_TooDetailedRequest;;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x1402;SE_StreamTooShort;;2;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h 0x2402;MT_TooGeneralRequest;;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x1403;SE_TooManyElements;;3;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h 0x2403;MT_NoMatch;;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x4500;HSPI_HalTimeoutRetval;;0;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h 0x2404;MT_Full;;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x4501;HSPI_HalBusyRetval;;1;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h 0x2405;MT_NewNodeCreated;;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x4502;HSPI_HalErrorRetval;;2;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h 0x3f01;DLEE_NoPacketFound;;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h
0x4601;HURT_UartReadFailure;;1;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h 0x3f02;DLEE_PossiblePacketLoss;;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h
0x4602;HURT_UartReadSizeMissmatch;;2;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h 0x2f01;ASC_TooLongForTargetType;;1;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x4603;HURT_UartRxBufferTooSmall;;3;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h 0x2f02;ASC_InvalidCharacters;;2;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x4801;HGIO_UnknownGpioId;;1;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x2f03;ASC_BufferTooSmall;;3;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x4802;HGIO_DriveGpioFailure;;2;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x1701;HHI_ObjectNotHealthy;;1;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h
0x4803;HGIO_GpioTypeFailure;;3;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x1702;HHI_InvalidHealthState;;2;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h
0x4804;HGIO_GpioInvalidInstance;;4;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x1703;HHI_IsExternallyControlled;;3;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h
0x4805;HGIO_GpioDuplicateDetected;;5;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x3201;CF_ObjectHasNoFunctions;;1;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h
0x4806;HGIO_GpioInitFailed;;6;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x3202;CF_AlreadyCommanding;;2;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h
0x4807;HGIO_GpioGetValueFailed;;7;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x3301;HF_IsBusy;;1;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h
0x4400;UXOS_ExecutionFinished;Execution of the current command has finished;0;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h 0x3302;HF_InvalidParameters;;2;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.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 0x3303;HF_ExecutionFinished;;3;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h
0x4402;UXOS_BytesRead;Some bytes have been read from the executing process;2;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h 0x3304;HF_InvalidActionId;;4;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h
0x4403;UXOS_CommandError;Command execution failed;3;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h 0x1000;TIM_UnsupportedTimeFormat;;0;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h
0x4404;UXOS_NoCommandLoadedOrPending;;4;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h 0x1001;TIM_NotEnoughInformationForTargetFormat;;1;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h
0x4406;UXOS_PcloseCallError;;6;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.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

1 Full ID (hex) Name Description Unique ID Subsytem Name File Path
2 0x0000 OK System-wide code for ok. 0 HasReturnvaluesIF fsfw/returnvalues/returnvalue.h
3 0x0001 Failed Unspecified system-wide code for failed. 1 HasReturnvaluesIF fsfw/returnvalues/returnvalue.h
4 0x60a0 0x63a0 CCSDS_CommandNotImplemented NVMB_KeyNotExists Received action message with unknown action id Specified key does not exist in json file 160 CCSDS_HANDLER NVM_PARAM_BASE mission/tmtc/CcsdsIpCoreHandler.h mission/memory/NVMParameterBase.h
5 0x63a0 0x6300 NVMB_KeyNotExists NVMB_Busy Specified key does not exist in json file 160 0 NVM_PARAM_BASE mission/memory/NVMParameterBase.h mission/system/objects/Stack5VHandler.h
6 0x6d01 0x52b0 ACSDTB_DetumbleNoSensordata RWHA_SpiWriteFailure No description 1 176 ACS_DETUMBLE RW_HANDLER mission/controller/acs/control/Detumble.h mission/devices/devicedefinitions/rwHelpers.h
7 0x6c01 0x52b1 ACSPTG_PtgctrlMekfInputInvalid RWHA_SpiReadFailure No description Used by the spi send function to tell a failing read call 1 177 ACS_PTG RW_HANDLER mission/controller/acs/control/PtgCtrl.h mission/devices/devicedefinitions/rwHelpers.h
8 0x6b01 0x52b2 ACSSAF_SafectrlMekfInputInvalid RWHA_MissingStartSign No description Can be used by the HDLC decoding mechanism to inform about a missing start sign 0x7E 1 178 ACS_SAFE RW_HANDLER mission/controller/acs/control/SafeCtrl.h mission/devices/devicedefinitions/rwHelpers.h
9 0x6a02 0x52b3 ACSMEKF_MekfUninitialized RWHA_InvalidSubstitute No description Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination 2 179 ACS_MEKF RW_HANDLER mission/controller/acs/MultiplicativeKalmanFilter.h mission/devices/devicedefinitions/rwHelpers.h
10 0x6a03 0x52b4 ACSMEKF_MekfNoGyrData RWHA_MissingEndSign No description HDLC decoding mechanism never receives the end sign 0x7E 3 180 ACS_MEKF RW_HANDLER mission/controller/acs/MultiplicativeKalmanFilter.h mission/devices/devicedefinitions/rwHelpers.h
11 0x6a04 0x52b5 ACSMEKF_MekfNoModelVectors RWHA_NoReply No description Reaction wheel only responds with empty frames. 4 181 ACS_MEKF RW_HANDLER mission/controller/acs/MultiplicativeKalmanFilter.h mission/devices/devicedefinitions/rwHelpers.h
12 0x6a05 0x52b6 ACSMEKF_MekfNoSusMgmStrData RWHA_NoStartMarker No description Expected a start marker as first byte 5 182 ACS_MEKF RW_HANDLER mission/controller/acs/MultiplicativeKalmanFilter.h mission/devices/devicedefinitions/rwHelpers.h
13 0x6a06 0x52b7 ACSMEKF_MekfCovarianceInversionFailed RWHA_SpiReadTimeout No description Timeout when reading reply 6 183 ACS_MEKF RW_HANDLER mission/controller/acs/MultiplicativeKalmanFilter.h mission/devices/devicedefinitions/rwHelpers.h
0x6a07 ACSMEKF_MekfInitialized No description 7 ACS_MEKF mission/controller/acs/MultiplicativeKalmanFilter.h
0x6a08 ACSMEKF_MekfRunning No description 8 ACS_MEKF mission/controller/acs/MultiplicativeKalmanFilter.h
0x6900 ACSCTRL_FileDeletionFailed No description 0 ACS_CTRL mission/controller/AcsController.h
0x52b0 RWHA_SpiWriteFailure No description 176 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
0x52b1 RWHA_SpiReadFailure Used by the spi send function to tell a failing read call 177 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.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/devicedefinitions/rwHelpers.h
0x52b3 RWHA_InvalidSubstitute Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination 179 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
0x52b4 RWHA_MissingEndSign HDLC decoding mechanism never receives the end sign 0x7E 180 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
0x52b5 RWHA_NoReply Reaction wheel only responds with empty frames. 181 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
0x52b6 RWHA_NoStartMarker Expected a start marker as first byte 182 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
0x52b7 RWHA_SpiReadTimeout Timeout when reading reply 183 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
0x5100 IMTQ_InvalidCommandCode No description 0 IMTQ_HANDLER mission/devices/devicedefinitions/imtqHelpers.h
0x5101 IMTQ_MgmMeasurementLowLevelError No description 1 IMTQ_HANDLER mission/devices/devicedefinitions/imtqHelpers.h
0x5102 IMTQ_ActuateCmdLowLevelError No description 2 IMTQ_HANDLER mission/devices/devicedefinitions/imtqHelpers.h
14 0x5103 0x58a0 IMTQ_ParameterMissing SUSS_ErrorUnlockMutex No description 3 160 IMTQ_HANDLER SUS_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SusHandler.h
15 0x5104 0x58a1 IMTQ_ParameterInvalid SUSS_ErrorLockMutex No description 4 161 IMTQ_HANDLER SUS_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SusHandler.h
16 0x5105 0x66a0 IMTQ_CcUnavailable SADPL_CommandNotSupported No description 5 160 IMTQ_HANDLER SA_DEPL_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SolarArrayDeploymentHandler.h
17 0x5106 0x66a1 IMTQ_InternalProcessingError SADPL_DeploymentAlreadyExecuting No description 6 161 IMTQ_HANDLER SA_DEPL_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SolarArrayDeploymentHandler.h
18 0x5107 0x66a2 IMTQ_RejectedWithoutReason SADPL_MainSwitchTimeoutFailure No description 7 162 IMTQ_HANDLER SA_DEPL_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SolarArrayDeploymentHandler.h
19 0x5108 0x66a3 IMTQ_CmdErrUnknown SADPL_SwitchingDeplSa1Failed No description 8 163 IMTQ_HANDLER SA_DEPL_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SolarArrayDeploymentHandler.h
20 0x51a7 0x66a4 IMTQ_UnexpectedSelfTestReply SADPL_SwitchingDeplSa2Failed The status reply to a self test command was received but no self test command has been sent. This should normally never happen. 167 164 IMTQ_HANDLER SA_DEPL_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SolarArrayDeploymentHandler.h
21 0x66a0 0x51a0 SADPL_CommandNotSupported IMTQ_InvalidSpeed No description Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000] 160 SA_DEPL_HANDLER IMTQ_HANDLER mission/devices/SolarArrayDeploymentHandler.h mission/devices/RwHandler.h
22 0x51a1 IMTQ_InvalidRampTime Action Message with invalid ramp time was received. 161 IMTQ_HANDLER mission/devices/RwHandler.h
23 0x51a2 IMTQ_SetSpeedCommandInvalidLength Received set speed command has invalid length. Should be 6. 162 IMTQ_HANDLER mission/devices/RwHandler.h
24 0x51a3 IMTQ_ExecutionFailed Command execution failed 163 IMTQ_HANDLER mission/devices/RwHandler.h
25 0x51a4 IMTQ_CrcError Reaction wheel reply has invalid crc 164 IMTQ_HANDLER mission/devices/RwHandler.h
26 0x51a5 IMTQ_ValueNotRead 165 IMTQ_HANDLER mission/devices/RwHandler.h
27 0x66a1 0x51a6 SADPL_DeploymentAlreadyExecuting IMTQ_CmdErrUnknown No description 161 166 SA_DEPL_HANDLER IMTQ_HANDLER mission/devices/SolarArrayDeploymentHandler.h mission/devices/ImtqHandler.h
28 0x66a2 0x51a7 SADPL_MainSwitchTimeoutFailure IMTQ_UnexpectedSelfTestReply No description The status reply to a self test command was received but no self test command has been sent. This should normally never happen. 162 167 SA_DEPL_HANDLER IMTQ_HANDLER mission/devices/SolarArrayDeploymentHandler.h mission/devices/ImtqHandler.h
29 0x66a3 0x50a0 SADPL_SwitchingDeplSa1Failed SYRLINKS_CrcFailure No description 163 160 SA_DEPL_HANDLER SYRLINKS_HANDLER mission/devices/SolarArrayDeploymentHandler.h mission/devices/SyrlinksHandler.h
35 0x50a4 0x50a6 SYRLINKS_BadEndOfFrameAck SYRLINKS_BadCrcAck No description 164 166 SYRLINKS_HANDLER mission/devices/SyrlinksHandler.h
36 0x50a5 0x50a7 SYRLINKS_UnknownCommandIdAck SYRLINKS_ReplyWrongSize No description 165 167 SYRLINKS_HANDLER mission/devices/SyrlinksHandler.h
37 0x50a6 0x50a8 SYRLINKS_BadCrcAck SYRLINKS_MissingStartFrameCharacter No description 166 168 SYRLINKS_HANDLER mission/devices/SyrlinksHandler.h
38 0x50a7 0x5d00 SYRLINKS_ReplyWrongSize GOMS_PacketTooLong No description 167 0 SYRLINKS_HANDLER GOM_SPACE_HANDLER mission/devices/SyrlinksHandler.h mission/devices/GomspaceDeviceHandler.h
39 0x50a8 0x5d01 SYRLINKS_MissingStartFrameCharacter GOMS_InvalidTableId No description 168 1 SYRLINKS_HANDLER GOM_SPACE_HANDLER mission/devices/SyrlinksHandler.h mission/devices/GomspaceDeviceHandler.h
40 0x58a0 0x5d02 SUSS_ErrorUnlockMutex GOMS_InvalidAddress No description 160 2 SUS_HANDLER GOM_SPACE_HANDLER mission/devices/SusHandler.h mission/devices/GomspaceDeviceHandler.h
41 0x58a1 0x5d03 SUSS_ErrorLockMutex GOMS_InvalidParamSize No description 161 3 SUS_HANDLER GOM_SPACE_HANDLER mission/devices/SusHandler.h mission/devices/GomspaceDeviceHandler.h
42 0x4fa1 0x5d04 HEATER_InvalidRampTime GOMS_InvalidPayloadSize Action Message with invalid ramp time was received. 161 4 HEATER_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h mission/devices/GomspaceDeviceHandler.h
43 0x4fa2 0x5d05 HEATER_SetSpeedCommandInvalidLength GOMS_UnknownReplyId Received set speed command has invalid length. Should be 6. 162 5 HEATER_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h mission/devices/GomspaceDeviceHandler.h
44 0x4fa3 0x4fa1 HEATER_ExecutionFailed HEATER_CommandNotSupported Command execution failed 163 161 HEATER_HANDLER mission/devices/RwHandler.h mission/devices/HeaterHandler.h
45 0x4fa2 HEATER_InitFailed 162 HEATER_HANDLER mission/devices/HeaterHandler.h
46 0x4fa3 HEATER_InvalidSwitchNr 163 HEATER_HANDLER mission/devices/HeaterHandler.h
47 0x4fa4 HEATER_MainSwitchSetTimeout 164 HEATER_HANDLER mission/devices/HeaterHandler.h
48 0x4fa5 HEATER_CommandAlreadyWaiting 165 HEATER_HANDLER mission/devices/HeaterHandler.h
49 0x60a0 CCSDS_CommandNotImplemented Received action message with unknown action id 160 CCSDS_HANDLER mission/tmtc/CcsdsIpCoreHandler.h
50 0x4fa4 0x6a01 HEATER_CrcError ACSSAF_SafectrlMekfInputInvalid Reaction wheel reply has invalid crc 164 1 HEATER_HANDLER ACS_SAFE mission/devices/RwHandler.h mission/controller/acs/control/SafeCtrl.h
51 0x6b01 ACSPTG_PtgctrlMekfInputInvalid 1 ACS_PTG mission/controller/acs/control/PtgCtrl.h
52 0x4fa5 0x6c01 HEATER_ValueNotRead ACSDTB_DetumbleNoSensordata No description 165 1 HEATER_HANDLER ACS_DETUMBLE mission/devices/RwHandler.h mission/controller/acs/control/Detumble.h
53 0x4fa0 0x6901 HEATER_InvalidSpeed ACSKAL_KalmanNoGyrMeas Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000] 160 1 HEATER_HANDLER ACS_KALMAN mission/devices/RwHandler.h mission/controller/acs/MultiplicativeKalmanFilter.h
54 0x5d00 0x6902 GOMS_PacketTooLong ACSKAL_KalmanNoModel No description 0 2 GOM_SPACE_HANDLER ACS_KALMAN mission/devices/GomspaceDeviceHandler.h mission/controller/acs/MultiplicativeKalmanFilter.h
55 0x5d01 0x6903 GOMS_InvalidTableId ACSKAL_KalmanInversionFailed No description 1 3 GOM_SPACE_HANDLER ACS_KALMAN mission/devices/GomspaceDeviceHandler.h mission/controller/acs/MultiplicativeKalmanFilter.h
56 0x5d02 0x4500 GOMS_InvalidAddress HSPI_OpeningFileFailed No description 2 0 GOM_SPACE_HANDLER HAL_SPI mission/devices/GomspaceDeviceHandler.h fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
57 0x5d03 0x4501 GOMS_InvalidParamSize HSPI_FullDuplexTransferFailed No description 3 1 GOM_SPACE_HANDLER HAL_SPI mission/devices/GomspaceDeviceHandler.h fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
58 0x5d04 0x4502 GOMS_InvalidPayloadSize HSPI_HalfDuplexTransferFailed No description 4 2 GOM_SPACE_HANDLER HAL_SPI mission/devices/GomspaceDeviceHandler.h fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
59 0x5d05 0x4801 GOMS_UnknownReplyId HGIO_UnknownGpioId No description 5 1 GOM_SPACE_HANDLER HAL_GPIO mission/devices/GomspaceDeviceHandler.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
60 0x38a1 0x4802 SGP4_InvalidEccentricity HGIO_DriveGpioFailure No description 161 2 SGP4PROPAGATOR_CLASS HAL_GPIO fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
61 0x38a2 0x4803 SGP4_InvalidMeanMotion HGIO_GpioTypeFailure No description 162 3 SGP4PROPAGATOR_CLASS HAL_GPIO fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
62 0x38a3 0x4804 SGP4_InvalidPerturbationElements HGIO_GpioInvalidInstance No description 163 4 SGP4PROPAGATOR_CLASS HAL_GPIO fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
63 0x38a4 0x4805 SGP4_InvalidSemiLatusRectum HGIO_GpioDuplicateDetected No description 164 5 SGP4PROPAGATOR_CLASS HAL_GPIO fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
64 0x38a5 0x4806 SGP4_InvalidEpochElements HGIO_GpioInitFailed No description 165 6 SGP4PROPAGATOR_CLASS HAL_GPIO fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
65 0x38a6 0x4807 SGP4_SatelliteHasDecayed HGIO_GpioGetValueFailed No description 166 7 SGP4PROPAGATOR_CLASS HAL_GPIO fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
66 0x38b1 0x4601 SGP4_TleTooOld HURT_UartReadFailure No description 177 1 SGP4PROPAGATOR_CLASS HAL_UART fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
67 0x38b2 0x4602 SGP4_TleNotInitialized HURT_UartReadSizeMissmatch No description 178 2 SGP4PROPAGATOR_CLASS HAL_UART fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
68 0x2801 0x4603 SM_DataTooLarge HURT_UartRxBufferTooSmall No description 1 3 STORAGE_MANAGER_IF HAL_UART fsfw/src/fsfw/storagemanager/StorageManagerIF.h fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
69 0x2802 0x4400 SM_DataStorageFull UXOS_ExecutionFinished No description Execution of the current command has finished 2 0 STORAGE_MANAGER_IF LINUX_OSAL fsfw/src/fsfw/storagemanager/StorageManagerIF.h fsfw/src/fsfw_hal/linux/CommandExecutor.h
70 0x2803 0x4401 SM_IllegalStorageId UXOS_CommandPending No description Command is pending. This will also be returned if the user tries to load another command but a command is still pending 3 1 STORAGE_MANAGER_IF LINUX_OSAL fsfw/src/fsfw/storagemanager/StorageManagerIF.h fsfw/src/fsfw_hal/linux/CommandExecutor.h
71 0x2804 0x4402 SM_DataDoesNotExist UXOS_BytesRead No description Some bytes have been read from the executing process 4 2 STORAGE_MANAGER_IF LINUX_OSAL fsfw/src/fsfw/storagemanager/StorageManagerIF.h fsfw/src/fsfw_hal/linux/CommandExecutor.h
72 0x2805 0x4403 SM_IllegalAddress UXOS_CommandError No description Command execution failed 5 3 STORAGE_MANAGER_IF LINUX_OSAL fsfw/src/fsfw/storagemanager/StorageManagerIF.h fsfw/src/fsfw_hal/linux/CommandExecutor.h
73 0x2806 0x4404 SM_PoolTooLarge UXOS_NoCommandLoadedOrPending No description 6 4 STORAGE_MANAGER_IF LINUX_OSAL fsfw/src/fsfw/storagemanager/StorageManagerIF.h fsfw/src/fsfw_hal/linux/CommandExecutor.h
74 0x1a01 0x4406 TRC_NotEnoughSensors UXOS_PcloseCallError No description 1 6 TRIPLE_REDUNDACY_CHECK LINUX_OSAL fsfw/src/fsfw/monitoring/TriplexMonitor.h fsfw/src/fsfw_hal/linux/CommandExecutor.h
75 0x1a02 0x2801 TRC_LowestValueOol SM_DataTooLarge No description 2 1 TRIPLE_REDUNDACY_CHECK STORAGE_MANAGER_IF fsfw/src/fsfw/monitoring/TriplexMonitor.h fsfw/src/fsfw/storagemanager/StorageManagerIF.h
76 0x1a03 0x2802 TRC_HighestValueOol SM_DataStorageFull No description 3 2 TRIPLE_REDUNDACY_CHECK STORAGE_MANAGER_IF fsfw/src/fsfw/monitoring/TriplexMonitor.h fsfw/src/fsfw/storagemanager/StorageManagerIF.h
77 0x1a04 0x2803 TRC_BothValuesOol SM_IllegalStorageId No description 4 3 TRIPLE_REDUNDACY_CHECK STORAGE_MANAGER_IF fsfw/src/fsfw/monitoring/TriplexMonitor.h fsfw/src/fsfw/storagemanager/StorageManagerIF.h
78 0x1a05 0x2804 TRC_DuplexOol SM_DataDoesNotExist No description 5 4 TRIPLE_REDUNDACY_CHECK STORAGE_MANAGER_IF fsfw/src/fsfw/monitoring/TriplexMonitor.h fsfw/src/fsfw/storagemanager/StorageManagerIF.h
79 0x3101 0x2805 LIM_Unchecked SM_IllegalAddress No description 1 5 LIMITS_IF STORAGE_MANAGER_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/storagemanager/StorageManagerIF.h
80 0x3102 0x2806 LIM_Invalid SM_PoolTooLarge No description 2 6 LIMITS_IF STORAGE_MANAGER_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/storagemanager/StorageManagerIF.h
81 0x3103 0x0601 LIM_Unselected PP_DoItMyself No description 3 1 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
82 0x3104 0x0602 LIM_BelowLowLimit PP_PointsToVariable No description 4 2 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
83 0x3105 0x0603 LIM_AboveHighLimit PP_PointsToMemory No description 5 3 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
84 0x3106 0x0604 LIM_UnexpectedValue PP_ActivityCompleted No description 6 4 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
85 0x3107 0x0605 LIM_OutOfRange PP_PointsToVectorUint8 No description 7 5 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
86 0x31a0 0x0606 LIM_FirstSample PP_PointsToVectorUint16 No description 160 6 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
87 0x31e0 0x0607 LIM_InvalidSize PP_PointsToVectorUint32 No description 224 7 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
88 0x31e1 0x0608 LIM_WrongType PP_PointsToVectorFloat No description 225 8 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
89 0x31e2 0x06a0 LIM_WrongPid PP_DumpNotSupported No description 226 160 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
90 0x31e3 0x06e0 LIM_WrongLimitId PP_InvalidSize No description 227 224 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
91 0x31ee 0x06e1 LIM_MonitorNotFound PP_InvalidAddress No description 238 225 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
92 0x2901 0x06e2 TC_InvalidTargetState PP_InvalidContent No description 1 226 THERMAL_COMPONENT_IF HAS_MEMORY_IF fsfw/src/fsfw/thermal/ThermalComponentIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
93 0x29f1 0x06e3 TC_AboveOperationalLimit PP_UnalignedAccess No description 241 227 THERMAL_COMPONENT_IF HAS_MEMORY_IF fsfw/src/fsfw/thermal/ThermalComponentIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
94 0x29f2 0x06e4 TC_BelowOperationalLimit PP_WriteProtected No description 242 228 THERMAL_COMPONENT_IF HAS_MEMORY_IF fsfw/src/fsfw/thermal/ThermalComponentIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
95 0x13e0 MH_UnknownCmd No description 224 MEMORY_HELPER fsfw/src/fsfw/memory/MemoryHelper.h
96 0x13e1 MH_InvalidAddress No description 225 MEMORY_HELPER fsfw/src/fsfw/memory/MemoryHelper.h
97 0x13e2 MH_InvalidSize No description 226 MEMORY_HELPER fsfw/src/fsfw/memory/MemoryHelper.h
98 0x13e3 MH_StateMismatch No description 227 MEMORY_HELPER fsfw/src/fsfw/memory/MemoryHelper.h
99 0x0601 0x38a1 PP_DoItMyself SGP4_InvalidEccentricity No description 1 161 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
100 0x0602 0x38a2 PP_PointsToVariable SGP4_InvalidMeanMotion No description 2 162 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
101 0x0603 0x38a3 PP_PointsToMemory SGP4_InvalidPerturbationElements No description 3 163 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
102 0x0604 0x38a4 PP_ActivityCompleted SGP4_InvalidSemiLatusRectum No description 4 164 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
103 0x0605 0x38a5 PP_PointsToVectorUint8 SGP4_InvalidEpochElements No description 5 165 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
104 0x0606 0x38a6 PP_PointsToVectorUint16 SGP4_SatelliteHasDecayed No description 6 166 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
105 0x0607 0x38b1 PP_PointsToVectorUint32 SGP4_TleTooOld No description 7 177 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
106 0x0608 0x38b2 PP_PointsToVectorFloat SGP4_TleNotInitialized No description 8 178 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
107 0x06a0 0x1801 PP_DumpNotSupported FF_Full No description 160 1 HAS_MEMORY_IF FIFO_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/container/FIFOBase.h
108 0x1802 FF_Empty 2 FIFO_CLASS fsfw/src/fsfw/container/FIFOBase.h
109 0x1601 FMM_MapFull 1 FIXED_MULTIMAP fsfw/src/fsfw/container/FixedOrderedMultimap.h
110 0x1602 FMM_KeyDoesNotExist 2 FIXED_MULTIMAP fsfw/src/fsfw/container/FixedOrderedMultimap.h
111 0x3901 MUX_NotEnoughResources 1 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
112 0x3902 MUX_InsufficientMemory 2 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
113 0x3903 MUX_NoPrivilege 3 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
114 0x3904 MUX_WrongAttributeSetting 4 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
115 0x3905 MUX_MutexAlreadyLocked 5 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
116 0x3906 MUX_MutexNotFound 6 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
117 0x3907 MUX_MutexMaxLocks 7 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
118 0x3908 MUX_CurrThreadAlreadyOwnsMutex 8 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
119 0x3909 MUX_CurrThreadDoesNotOwnMutex 9 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
120 0x390a MUX_MutexTimeout 10 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
121 0x390b MUX_MutexInvalidId 11 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
122 0x390c MUX_MutexDestroyedWhileWaiting 12 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
123 0x3a01 MQI_Empty 1 MESSAGE_QUEUE_IF fsfw/src/fsfw/ipc/MessageQueueIF.h
124 0x3a02 MQI_Full No space left for more messages 2 MESSAGE_QUEUE_IF fsfw/src/fsfw/ipc/MessageQueueIF.h
125 0x3a03 MQI_NoReplyPartner Returned if a reply method was called without partner 3 MESSAGE_QUEUE_IF fsfw/src/fsfw/ipc/MessageQueueIF.h
126 0x3a04 MQI_DestinationInvalid Returned if the target destination is invalid. 4 MESSAGE_QUEUE_IF fsfw/src/fsfw/ipc/MessageQueueIF.h
127 0x0f01 CM_UnknownCommand 1 COMMAND_MESSAGE fsfw/src/fsfw/ipc/CommandMessageIF.h
128 0x06e0 0x0e01 PP_InvalidSize HM_InvalidMode No description 224 1 HAS_MEMORY_IF HAS_MODES_IF fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/modes/HasModesIF.h
129 0x06e1 0x0e02 PP_InvalidAddress HM_TransNotAllowed No description 225 2 HAS_MEMORY_IF HAS_MODES_IF fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/modes/HasModesIF.h
130 0x06e2 0x0e03 PP_InvalidContent HM_InTransition No description 226 3 HAS_MEMORY_IF HAS_MODES_IF fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/modes/HasModesIF.h
131 0x06e3 0x0e04 PP_UnalignedAccess HM_InvalidSubmode No description 227 4 HAS_MEMORY_IF HAS_MODES_IF fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/modes/HasModesIF.h
132 0x06e4 0x0c02 PP_WriteProtected MS_InvalidEntry No description 228 2 HAS_MEMORY_IF MODE_STORE_IF fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
133 0x4c00 0x0c03 SPPA_NoPacketFound MS_TooManyElements No description 0 3 SPACE_PACKET_PARSER MODE_STORE_IF fsfw/src/fsfw/tmtcservices/SpacePacketParser.h fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
134 0x4c01 0x0c04 SPPA_SplitPacket MS_CantStoreEmpty No description 1 4 SPACE_PACKET_PARSER MODE_STORE_IF fsfw/src/fsfw/tmtcservices/SpacePacketParser.h fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
135 0x1d01 0x0b01 ATC_ActivityStarted SB_ChildNotFound No description 1 ACCEPTS_TELECOMMANDS_IF SUBSYSTEM_BASE fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h fsfw/src/fsfw/subsystem/SubsystemBase.h
136 0x1d02 0x0b02 ATC_InvalidSubservice SB_ChildInfoUpdated No description 2 ACCEPTS_TELECOMMANDS_IF SUBSYSTEM_BASE fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h fsfw/src/fsfw/subsystem/SubsystemBase.h
137 0x1d03 0x0b03 ATC_IllegalApplicationData SB_ChildDoesntHaveModes No description 3 ACCEPTS_TELECOMMANDS_IF SUBSYSTEM_BASE fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h fsfw/src/fsfw/subsystem/SubsystemBase.h
138 0x1d04 0x0b04 ATC_SendTmFailed SB_CouldNotInsertChild No description 4 ACCEPTS_TELECOMMANDS_IF SUBSYSTEM_BASE fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h fsfw/src/fsfw/subsystem/SubsystemBase.h
139 0x1d05 0x0b05 ATC_Timeout SB_TableContainsInvalidObjectId No description 5 ACCEPTS_TELECOMMANDS_IF SUBSYSTEM_BASE fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h fsfw/src/fsfw/subsystem/SubsystemBase.h
140 0x2001 0x0d01 CSB_ExecutionComplete SS_SequenceAlreadyExists No description 1 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
141 0x2002 0x0d02 CSB_NoStepMessage SS_TableAlreadyExists No description 2 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
142 0x2003 0x0d03 CSB_ObjectBusy SS_TableDoesNotExist No description 3 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
143 0x2004 0x0d04 CSB_Busy SS_TableOrSequenceLengthInvalid No description 4 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
144 0x2005 0x0d05 CSB_InvalidTc SS_SequenceDoesNotExist No description 5 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
145 0x2006 0x0d06 CSB_InvalidObject SS_TableContainsInvalidObjectId No description 6 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
146 0x2007 0x0d07 CSB_InvalidReply SS_FallbackSequenceDoesNotExist No description 7 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
147 0x3da0 0x0d08 PVA_InvalidReadWriteMode SS_NoTargetTable No description 160 8 POOL_VARIABLE_IF SUBSYSTEM fsfw/src/fsfw/datapool/PoolVariableIF.h fsfw/src/fsfw/subsystem/Subsystem.h
148 0x3da1 0x0d09 PVA_InvalidPoolEntry SS_SequenceOrTableTooLong No description 161 9 POOL_VARIABLE_IF SUBSYSTEM fsfw/src/fsfw/datapool/PoolVariableIF.h fsfw/src/fsfw/subsystem/Subsystem.h
149 0x0801 0x0d0b DPS_InvalidParameterDefinition SS_IsFallbackSequence No description 1 11 DATA_SET_CLASS SUBSYSTEM fsfw/src/fsfw/datapool/DataSetIF.h fsfw/src/fsfw/subsystem/Subsystem.h
150 0x0802 0x0d0c DPS_SetWasAlreadyRead SS_AccessDenied No description 2 12 DATA_SET_CLASS SUBSYSTEM fsfw/src/fsfw/datapool/DataSetIF.h fsfw/src/fsfw/subsystem/Subsystem.h
151 0x0803 0x0d0e DPS_CommitingWithoutReading SS_TableInUse No description 3 14 DATA_SET_CLASS SUBSYSTEM fsfw/src/fsfw/datapool/DataSetIF.h fsfw/src/fsfw/subsystem/Subsystem.h
152 0x0804 0x0da1 DPS_DataSetUninitialised SS_TargetTableNotReached No description 4 161 DATA_SET_CLASS SUBSYSTEM fsfw/src/fsfw/datapool/DataSetIF.h fsfw/src/fsfw/subsystem/Subsystem.h
153 0x0805 0x0da2 DPS_DataSetFull SS_TableCheckFailed No description 5 162 DATA_SET_CLASS SUBSYSTEM fsfw/src/fsfw/datapool/DataSetIF.h fsfw/src/fsfw/subsystem/Subsystem.h
154 0x0806 0x2501 DPS_PoolVarNull EV_ListenerNotFound No description 6 1 DATA_SET_CLASS EVENT_MANAGER_IF fsfw/src/fsfw/datapool/DataSetIF.h fsfw/src/fsfw/events/EventManagerIF.h
0x3a01 MQI_Empty No description 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 No description 1 COMMAND_MESSAGE fsfw/src/fsfw/ipc/CommandMessageIF.h
0x3901 MUX_NotEnoughResources No description 1 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3902 MUX_InsufficientMemory No description 2 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3903 MUX_NoPrivilege No description 3 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3904 MUX_WrongAttributeSetting No description 4 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3905 MUX_MutexAlreadyLocked No description 5 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3906 MUX_MutexNotFound No description 6 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3907 MUX_MutexMaxLocks No description 7 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3908 MUX_CurrThreadAlreadyOwnsMutex No description 8 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3909 MUX_CurrThreadDoesNotOwnMutex No description 9 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x390a MUX_MutexTimeout No description 10 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x390b MUX_MutexInvalidId No description 11 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x390c MUX_MutexDestroyedWhileWaiting No description 12 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x1601 FMM_MapFull No description 1 FIXED_MULTIMAP fsfw/src/fsfw/container/FixedOrderedMultimap.h
0x1602 FMM_KeyDoesNotExist No description 2 FIXED_MULTIMAP fsfw/src/fsfw/container/FixedOrderedMultimap.h
0x1801 FF_Full No description 1 FIFO_CLASS fsfw/src/fsfw/container/FIFOBase.h
0x1802 FF_Empty No description 2 FIFO_CLASS fsfw/src/fsfw/container/FIFOBase.h
0x03a0 DHB_InvalidChannel No description 160 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03b0 DHB_AperiodicReply No description 176 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03b1 DHB_IgnoreReplyData No description 177 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03b2 DHB_IgnoreFullPacket No description 178 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03c0 DHB_NothingToSend No description 192 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03c2 DHB_CommandMapError No description 194 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03d0 DHB_NoSwitch No description 208 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03e0 DHB_ChildTimeout No description 224 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03e1 DHB_SwitchFailed No description 225 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x1201 AB_NeedSecondStep No description 1 ASSEMBLY_BASE fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x1202 AB_NeedToReconfigure No description 2 ASSEMBLY_BASE fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x1203 AB_ModeFallback No description 3 ASSEMBLY_BASE fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x1204 AB_ChildNotCommandable No description 4 ASSEMBLY_BASE fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x1205 AB_NeedToChangeHealth No description 5 ASSEMBLY_BASE fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x12a1 AB_NotEnoughChildrenInCorrectState No description 161 ASSEMBLY_BASE fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x27a0 DHI_NoCommandData No description 160 DEVICE_HANDLER_IF fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
0x27a1 DHI_CommandNotSupported No description 161 DEVICE_HANDLER_IF fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
0x27a2 DHI_CommandAlreadySent No description 162 DEVICE_HANDLER_IF fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
0x27a3 DHI_CommandWasNotSent No description 163 DEVICE_HANDLER_IF fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
155 0x27a4 0x04e1 DHI_CantSwitchAddress RMP_CommandNoDescriptorsAvailable No description 164 225 DEVICE_HANDLER_IF RMAP_CHANNEL fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h fsfw/src/fsfw/rmap/RMAP.h
156 0x27a5 0x04e2 DHI_WrongModeForCommand RMP_CommandBufferFull No description 165 226 DEVICE_HANDLER_IF RMAP_CHANNEL fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h fsfw/src/fsfw/rmap/RMAP.h
157 0x27a6 0x04e3 DHI_Timeout RMP_CommandChannelOutOfRange No description 166 227 DEVICE_HANDLER_IF RMAP_CHANNEL fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h fsfw/src/fsfw/rmap/RMAP.h
192 0x3609 0x040a CFDP_FilestoreResponseCantParseFsMessage RMP_ReplyCommandNotImplementedOrNotAuthorised No description 9 10 CFDP RMAP_CHANNEL fsfw/src/fsfw/cfdp/definitions.h fsfw/src/fsfw/rmap/RMAP.h
193 0x360a 0x040b CFDP_InvalidPduFormat RMP_ReplyRmwDataLengthError No description 10 11 CFDP RMAP_CHANNEL fsfw/src/fsfw/cfdp/definitions.h fsfw/src/fsfw/rmap/RMAP.h
194 0x04e1 0x040c RMP_CommandNoDescriptorsAvailable RMP_ReplyInvalidTargetLogicalAddress No description 225 12 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
195 0x04e2 0x1401 RMP_CommandBufferFull SE_BufferTooShort No description 226 1 RMAP_CHANNEL SERIALIZE_IF fsfw/src/fsfw/rmap/RMAP.h fsfw/src/fsfw/serialize/SerializeIF.h
196 0x04e3 0x1402 RMP_CommandChannelOutOfRange SE_StreamTooShort No description 227 2 RMAP_CHANNEL SERIALIZE_IF fsfw/src/fsfw/rmap/RMAP.h fsfw/src/fsfw/serialize/SerializeIF.h
197 0x04e6 0x1403 RMP_CommandChannelDeactivated SE_TooManyElements No description 230 3 RMAP_CHANNEL SERIALIZE_IF fsfw/src/fsfw/rmap/RMAP.h fsfw/src/fsfw/serialize/SerializeIF.h
0x04e7 RMP_CommandPortOutOfRange No description 231 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04e8 RMP_CommandPortInUse No description 232 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04e9 RMP_CommandNoChannel No description 233 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04ea RMP_NoHwCrc No description 234 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04d0 RMP_ReplyNoReply No description 208 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04d1 RMP_ReplyNotSent No description 209 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04d2 RMP_ReplyNotYetSent No description 210 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04d3 RMP_ReplyMissmatch No description 211 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04d4 RMP_ReplyTimeout No description 212 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04c0 RMP_ReplyInterfaceBusy No description 192 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04c1 RMP_ReplyTransmissionError No description 193 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04c2 RMP_ReplyInvalidData No description 194 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04c3 RMP_ReplyNotSupported No description 195 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f0 RMP_LinkDown No description 240 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f1 RMP_SpwCredit No description 241 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f2 RMP_SpwEscape No description 242 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f3 RMP_SpwDisconnect No description 243 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f4 RMP_SpwParity No description 244 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f5 RMP_SpwWriteSync No description 245 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f6 RMP_SpwInvalidAddress No description 246 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f7 RMP_SpwEarlyEop No description 247 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f8 RMP_SpwDma No description 248 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f9 RMP_SpwLinkError No description 249 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0400 RMP_ReplyOk No description 0 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0401 RMP_ReplyGeneralErrorCode No description 1 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0402 RMP_ReplyUnusedPacketTypeOrCommandCode No description 2 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0403 RMP_ReplyInvalidKey No description 3 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0404 RMP_ReplyInvalidDataCrc No description 4 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0405 RMP_ReplyEarlyEop No description 5 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0406 RMP_ReplyTooMuchData No description 6 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0407 RMP_ReplyEep No description 7 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0408 RMP_ReplyReserved No description 8 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0409 RMP_ReplyVerifyBufferOverrun No description 9 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x040a RMP_ReplyCommandNotImplementedOrNotAuthorised No description 10 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x040b RMP_ReplyRmwDataLengthError No description 11 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x040c RMP_ReplyInvalidTargetLogicalAddress No description 12 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x3b01 SPH_SemaphoreTimeout No description 1 SEMAPHORE_IF fsfw/src/fsfw/tasks/SemaphoreIF.h
0x3b02 SPH_SemaphoreNotOwned No description 2 SEMAPHORE_IF fsfw/src/fsfw/tasks/SemaphoreIF.h
0x3b03 SPH_SemaphoreInvalid No description 3 SEMAPHORE_IF fsfw/src/fsfw/tasks/SemaphoreIF.h
0x0e01 HM_InvalidMode No description 1 HAS_MODES_IF fsfw/src/fsfw/modes/HasModesIF.h
0x0e02 HM_TransNotAllowed No description 2 HAS_MODES_IF fsfw/src/fsfw/modes/HasModesIF.h
0x0e03 HM_InTransition No description 3 HAS_MODES_IF fsfw/src/fsfw/modes/HasModesIF.h
0x0e04 HM_InvalidSubmode No description 4 HAS_MODES_IF fsfw/src/fsfw/modes/HasModesIF.h
0x2101 TMB_Busy No description 1 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2102 TMB_Full No description 2 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2103 TMB_Empty No description 3 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2104 TMB_NullRequested No description 4 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2105 TMB_TooLarge No description 5 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2106 TMB_NotReady No description 6 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2107 TMB_DumpError No description 7 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2108 TMB_CrcError No description 8 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2109 TMB_Timeout No description 9 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210a TMB_IdlePacketFound No description 10 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210b TMB_TelecommandFound No description 11 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210c TMB_NoPusATm No description 12 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210d TMB_TooSmall No description 13 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210e TMB_BlockNotFound No description 14 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210f TMB_InvalidRequest No description 15 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2201 TMF_Busy No description 1 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2202 TMF_LastPacketFound No description 2 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2203 TMF_StopFetch No description 3 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2204 TMF_Timeout No description 4 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2205 TMF_TmChannelFull No description 5 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2206 TMF_NotStored No description 6 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2207 TMF_AllDeleted No description 7 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2208 TMF_InvalidData No description 8 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2209 TMF_NotReady No description 9 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x1e00 PUS_InvalidPusVersion No description 0 PUS_IF fsfw/src/fsfw/tmtcpacket/pus/PusIF.h
0x1e01 PUS_InvalidCrc16 No description 1 PUS_IF fsfw/src/fsfw/tmtcpacket/pus/PusIF.h
0x2501 EV_ListenerNotFound No description 1 EVENT_MANAGER_IF fsfw/src/fsfw/events/EventManagerIF.h
0x1000 TIM_UnsupportedTimeFormat No description 0 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
0x1001 TIM_NotEnoughInformationForTargetFormat No description 1 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
0x1002 TIM_LengthMismatch No description 2 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
0x1003 TIM_InvalidTimeFormat No description 3 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
0x1004 TIM_InvalidDayOfYear No description 4 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
0x1005 TIM_TimeDoesNotFitFormat No description 5 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
0x3701 TSI_BadTimestamp No description 1 TIME_STAMPER_IF fsfw/src/fsfw/timemanager/TimeStampIF.h
0x3001 POS_InPowerTransition No description 1 POWER_SWITCHER fsfw/src/fsfw/power/PowerSwitcher.h
0x3002 POS_SwitchStateMismatch No description 2 POWER_SWITCHER fsfw/src/fsfw/power/PowerSwitcher.h
0x0501 PS_SwitchOn No description 1 POWER_SWITCH_IF fsfw/src/fsfw/power/PowerSwitchIF.h
0x0500 PS_SwitchOff No description 0 POWER_SWITCH_IF fsfw/src/fsfw/power/PowerSwitchIF.h
0x0502 PS_SwitchTimeout No description 2 POWER_SWITCH_IF fsfw/src/fsfw/power/PowerSwitchIF.h
0x0503 PS_FuseOn No description 3 POWER_SWITCH_IF fsfw/src/fsfw/power/PowerSwitchIF.h
0x0504 PS_FuseOff No description 4 POWER_SWITCH_IF fsfw/src/fsfw/power/PowerSwitchIF.h
0x0201 OM_InsertionFailed No description 1 OBJECT_MANAGER_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h
0x0202 OM_NotFound No description 2 OBJECT_MANAGER_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h
198 0x0203 0x3da0 OM_ChildInitFailed PVA_InvalidReadWriteMode No description 3 160 OBJECT_MANAGER_IF POOL_VARIABLE_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h fsfw/src/fsfw/datapool/PoolVariableIF.h
199 0x0204 0x3da1 OM_InternalErrReporterUninit PVA_InvalidPoolEntry No description 4 161 OBJECT_MANAGER_IF POOL_VARIABLE_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h fsfw/src/fsfw/datapool/PoolVariableIF.h
200 0x2e01 0x0801 HPA_InvalidIdentifierId DPS_InvalidParameterDefinition No description 1 HAS_PARAMETERS_IF DATA_SET_CLASS fsfw/src/fsfw/parameters/HasParametersIF.h fsfw/src/fsfw/datapool/DataSetIF.h
203 0x2e05 0x0804 HPA_ReadOnly DPS_DataSetUninitialised No description 5 4 HAS_PARAMETERS_IF DATA_SET_CLASS fsfw/src/fsfw/parameters/HasParametersIF.h fsfw/src/fsfw/datapool/DataSetIF.h
204 0x2d01 0x0805 PAW_UnknownDatatype DPS_DataSetFull No description 1 5 PARAMETER_WRAPPER DATA_SET_CLASS fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/datapool/DataSetIF.h
205 0x2d02 0x0806 PAW_DatatypeMissmatch DPS_PoolVarNull No description 2 6 PARAMETER_WRAPPER DATA_SET_CLASS fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/datapool/DataSetIF.h
206 0x2d03 0x1c01 PAW_Readonly TCD_PacketLost No description 3 1 PARAMETER_WRAPPER PACKET_DISTRIBUTION fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
207 0x2d04 0x1c02 PAW_TooBig TCD_DestinationNotFound No description 4 2 PARAMETER_WRAPPER PACKET_DISTRIBUTION fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
208 0x2d05 0x1c03 PAW_SourceNotSet TCD_ServiceIdAlreadyExists No description 5 3 PARAMETER_WRAPPER PACKET_DISTRIBUTION fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
209 0x2d06 0x1b00 PAW_OutOfBounds TCC_NoDestinationFound No description 6 0 PARAMETER_WRAPPER TMTC_DISTRIBUTION fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/tcdistribution/definitions.h
210 0x2d07 0x1b01 PAW_NotSet TCC_InvalidCcsdsVersion No description 7 1 PARAMETER_WRAPPER TMTC_DISTRIBUTION fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/tcdistribution/definitions.h
211 0x2d08 0x1b02 PAW_ColumnOrRowsZero TCC_InvalidApid No description 8 2 PARAMETER_WRAPPER TMTC_DISTRIBUTION fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/tcdistribution/definitions.h
212 0x2401 0x1b03 MT_TooDetailedRequest TCC_InvalidPacketType No description 1 3 MATCH_TREE_CLASS TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/matching/MatchTree.h fsfw/src/fsfw/tcdistribution/definitions.h
213 0x2402 0x1b04 MT_TooGeneralRequest TCC_InvalidSecHeaderField No description 2 4 MATCH_TREE_CLASS TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/matching/MatchTree.h fsfw/src/fsfw/tcdistribution/definitions.h
214 0x2403 0x1b05 MT_NoMatch TCC_IncorrectPrimaryHeader No description 3 5 MATCH_TREE_CLASS TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/matching/MatchTree.h fsfw/src/fsfw/tcdistribution/definitions.h
215 0x2404 0x1b07 MT_Full TCC_IncompletePacket No description 4 7 MATCH_TREE_CLASS TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/matching/MatchTree.h fsfw/src/fsfw/tcdistribution/definitions.h
216 0x2405 0x1b08 MT_NewNodeCreated TCC_InvalidPusVersion No description 5 8 MATCH_TREE_CLASS TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/matching/MatchTree.h fsfw/src/fsfw/tcdistribution/definitions.h
217 0x3f01 0x1b09 DLEE_NoPacketFound TCC_IncorrectChecksum No description 1 9 DLE_ENCODER TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/DleParser.h fsfw/src/fsfw/tcdistribution/definitions.h
218 0x3f02 0x1b0a DLEE_PossiblePacketLoss TCC_IllegalPacketSubtype No description 2 10 DLE_ENCODER TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/DleParser.h fsfw/src/fsfw/tcdistribution/definitions.h
219 0x2f01 0x1b0b ASC_TooLongForTargetType TCC_IncorrectSecondaryHeader No description 1 11 ASCII_CONVERTER TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/AsciiConverter.h fsfw/src/fsfw/tcdistribution/definitions.h
0x2f02 ASC_InvalidCharacters No description 2 ASCII_CONVERTER fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x2f03 ASC_BufferTooSmall No description 3 ASCII_CONVERTER fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x1c01 TCD_PacketLost No description 1 PACKET_DISTRIBUTION fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1c02 TCD_DestinationNotFound No description 2 PACKET_DISTRIBUTION fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1c03 TCD_ServiceIdAlreadyExists No description 3 PACKET_DISTRIBUTION fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1b00 TCC_NoDestinationFound No description 0 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b01 TCC_InvalidCcsdsVersion No description 1 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b02 TCC_InvalidApid No description 2 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b03 TCC_InvalidPacketType No description 3 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b04 TCC_InvalidSecHeaderField No description 4 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b05 TCC_IncorrectPrimaryHeader No description 5 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b07 TCC_IncompletePacket No description 7 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b08 TCC_InvalidPusVersion No description 8 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b09 TCC_IncorrectChecksum No description 9 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b0a TCC_IllegalPacketSubtype No description 10 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
220 0x1b0b 0x3001 TCC_IncorrectSecondaryHeader POS_InPowerTransition No description 11 1 TMTC_DISTRIBUTION POWER_SWITCHER fsfw/src/fsfw/tcdistribution/definitions.h fsfw/src/fsfw/power/PowerSwitcher.h
221 0x1701 0x3002 HHI_ObjectNotHealthy POS_SwitchStateMismatch No description 1 2 HAS_HEALTH_IF POWER_SWITCHER fsfw/src/fsfw/health/HasHealthIF.h fsfw/src/fsfw/power/PowerSwitcher.h
222 0x1702 0x0501 HHI_InvalidHealthState PS_SwitchOn No description 2 1 HAS_HEALTH_IF POWER_SWITCH_IF fsfw/src/fsfw/health/HasHealthIF.h fsfw/src/fsfw/power/PowerSwitchIF.h
224 0x0c02 0x0502 MS_InvalidEntry PS_SwitchTimeout No description 2 MODE_STORE_IF POWER_SWITCH_IF fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h fsfw/src/fsfw/power/PowerSwitchIF.h
225 0x0c03 0x0503 MS_TooManyElements PS_FuseOn No description 3 MODE_STORE_IF POWER_SWITCH_IF fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h fsfw/src/fsfw/power/PowerSwitchIF.h
226 0x0c04 0x0504 MS_CantStoreEmpty PS_FuseOff No description 4 MODE_STORE_IF POWER_SWITCH_IF fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h fsfw/src/fsfw/power/PowerSwitchIF.h
227 0x0d01 0x3b00 SS_SequenceAlreadyExists SPH_ConnBroken No description 1 0 SUBSYSTEM SEMAPHORE_IF fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/common/TcpTmTcServer.h
228 0x0d02 0x2a01 SS_TableAlreadyExists IEC_NoConfigurationTable No description 2 1 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
229 0x0d03 0x2a02 SS_TableDoesNotExist IEC_NoCpuTable No description 3 2 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
230 0x0d04 0x2a03 SS_TableOrSequenceLengthInvalid IEC_InvalidWorkspaceAddress No description 4 3 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
231 0x0d05 0x2a04 SS_SequenceDoesNotExist IEC_TooLittleWorkspace No description 5 4 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
232 0x0d06 0x2a05 SS_TableContainsInvalidObjectId IEC_WorkspaceAllocation No description 6 5 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
233 0x0d07 0x2a06 SS_FallbackSequenceDoesNotExist IEC_InterruptStackTooSmall No description 7 6 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
234 0x0d08 0x2a07 SS_NoTargetTable IEC_ThreadExitted No description 8 7 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
235 0x0d09 0x2a08 SS_SequenceOrTableTooLong IEC_InconsistentMpInformation No description 9 8 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
236 0x0d0b 0x2a09 SS_IsFallbackSequence IEC_InvalidNode No description 11 9 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
237 0x0d0c 0x2a0a SS_AccessDenied IEC_NoMpci No description 12 10 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
238 0x0d0e 0x2a0b SS_TableInUse IEC_BadPacket No description 14 11 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
239 0x0da1 0x2a0c SS_TargetTableNotReached IEC_OutOfPackets No description 161 12 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
240 0x0da2 0x2a0d SS_TableCheckFailed IEC_OutOfGlobalObjects No description 162 13 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
241 0x0b01 0x2a0e SB_ChildNotFound IEC_OutOfProxies No description 1 14 SUBSYSTEM_BASE INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/SubsystemBase.h fsfw/src/fsfw/osal/InternalErrorCodes.h
242 0x0b02 0x2a0f SB_ChildInfoUpdated IEC_InvalidGlobalId No description 2 15 SUBSYSTEM_BASE INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/SubsystemBase.h fsfw/src/fsfw/osal/InternalErrorCodes.h
243 0x0b03 0x2a10 SB_ChildDoesntHaveModes IEC_BadStackHook No description 3 16 SUBSYSTEM_BASE INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/SubsystemBase.h fsfw/src/fsfw/osal/InternalErrorCodes.h
244 0x2a11 IEC_BadAttributes 17 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
245 0x2a12 IEC_ImplementationKeyCreateInconsistency 18 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
246 0x2a13 IEC_ImplementationBlockingOperationCancel 19 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
247 0x2a14 IEC_MutexObtainFromBadState 20 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
248 0x2a15 IEC_UnlimitedAndMaximumIs0 21 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
249 0x2600 FDI_YourFault 0 HANDLES_FAILURES_IF fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h
250 0x2601 FDI_MyFault 1 HANDLES_FAILURES_IF fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h
251 0x2602 FDI_ConfirmLater 2 HANDLES_FAILURES_IF fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h
252 0x1e00 PUS_InvalidPusVersion 0 PUS_IF fsfw/src/fsfw/tmtcpacket/pus/PusIF.h
253 0x1e01 PUS_InvalidCrc16 1 PUS_IF fsfw/src/fsfw/tmtcpacket/pus/PusIF.h
254 0x0201 OM_InsertionFailed 1 OBJECT_MANAGER_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h
255 0x0202 OM_NotFound 2 OBJECT_MANAGER_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h
256 0x0203 OM_ChildInitFailed 3 OBJECT_MANAGER_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h
257 0x0204 OM_InternalErrReporterUninit 4 OBJECT_MANAGER_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h
258 0x2201 TMF_Busy 1 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
259 0x2202 TMF_LastPacketFound 2 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
260 0x2203 TMF_StopFetch 3 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
261 0x2204 TMF_Timeout 4 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
262 0x2205 TMF_TmChannelFull 5 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
263 0x2206 TMF_NotStored 6 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
264 0x2207 TMF_AllDeleted 7 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
265 0x2208 TMF_InvalidData 8 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
266 0x2209 TMF_NotReady 9 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
267 0x2101 TMB_Busy 1 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
268 0x2102 TMB_Full 2 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
269 0x2103 TMB_Empty 3 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
270 0x2104 TMB_NullRequested 4 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
271 0x2105 TMB_TooLarge 5 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
272 0x2106 TMB_NotReady 6 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
273 0x2107 TMB_DumpError 7 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
274 0x2108 TMB_CrcError 8 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
275 0x2109 TMB_Timeout 9 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
276 0x210a TMB_IdlePacketFound 10 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
277 0x210b TMB_TelecommandFound 11 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
278 0x210c TMB_NoPusATm 12 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
279 0x210d TMB_TooSmall 13 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
280 0x210e TMB_BlockNotFound 14 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
281 0x210f TMB_InvalidRequest 15 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
282 0x2d01 PAW_UnknownDatatype 1 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
283 0x2d02 PAW_DatatypeMissmatch 2 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
284 0x2d03 PAW_Readonly 3 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
285 0x2d04 PAW_TooBig 4 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
286 0x2d05 PAW_SourceNotSet 5 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
287 0x2d06 PAW_OutOfBounds 6 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
288 0x2d07 PAW_NotSet 7 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
289 0x2d08 PAW_ColumnOrRowsZero 8 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
290 0x2e01 HPA_InvalidIdentifierId 1 HAS_PARAMETERS_IF fsfw/src/fsfw/parameters/HasParametersIF.h
291 0x2e02 HPA_InvalidDomainId 2 HAS_PARAMETERS_IF fsfw/src/fsfw/parameters/HasParametersIF.h
292 0x2e03 HPA_InvalidValue 3 HAS_PARAMETERS_IF fsfw/src/fsfw/parameters/HasParametersIF.h
293 0x2e05 HPA_ReadOnly 5 HAS_PARAMETERS_IF fsfw/src/fsfw/parameters/HasParametersIF.h
294 0x3b01 SPH_SemaphoreTimeout 1 SEMAPHORE_IF fsfw/src/fsfw/tasks/SemaphoreIF.h
295 0x3b02 SPH_SemaphoreNotOwned 2 SEMAPHORE_IF fsfw/src/fsfw/tasks/SemaphoreIF.h
296 0x3b03 SPH_SemaphoreInvalid 3 SEMAPHORE_IF fsfw/src/fsfw/tasks/SemaphoreIF.h
297 0x0b04 0x1a01 SB_CouldNotInsertChild TRC_NotEnoughSensors No description 4 1 SUBSYSTEM_BASE TRIPLE_REDUNDACY_CHECK fsfw/src/fsfw/subsystem/SubsystemBase.h fsfw/src/fsfw/monitoring/TriplexMonitor.h
298 0x0b05 0x1a02 SB_TableContainsInvalidObjectId TRC_LowestValueOol No description 5 2 SUBSYSTEM_BASE TRIPLE_REDUNDACY_CHECK fsfw/src/fsfw/subsystem/SubsystemBase.h fsfw/src/fsfw/monitoring/TriplexMonitor.h
299 0x3e00 0x1a03 HKM_QueueOrDestinationInvalid TRC_HighestValueOol No description 0 3 HOUSEKEEPING_MANAGER TRIPLE_REDUNDACY_CHECK fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h fsfw/src/fsfw/monitoring/TriplexMonitor.h
312 0x4305 0x31e2 FILS_InvalidParameters LIM_WrongPid No description 5 226 FILE_SYSTEM LIMITS_IF fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/monitoring/MonitoringIF.h
313 0x430a 0x31e3 FILS_FileDoesNotExist LIM_WrongLimitId No description 10 227 FILE_SYSTEM LIMITS_IF fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/monitoring/MonitoringIF.h
314 0x430b 0x31ee FILS_FileAlreadyExists LIM_MonitorNotFound No description 11 238 FILE_SYSTEM LIMITS_IF fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/monitoring/MonitoringIF.h
315 0x3601 CFDP_InvalidTlvType 1 CFDP fsfw/src/fsfw/cfdp/definitions.h
316 0x3602 CFDP_InvalidDirectiveField 2 CFDP fsfw/src/fsfw/cfdp/definitions.h
317 0x3603 CFDP_InvalidPduDatafieldLen 3 CFDP fsfw/src/fsfw/cfdp/definitions.h
318 0x3604 CFDP_InvalidAckDirectiveFields 4 CFDP fsfw/src/fsfw/cfdp/definitions.h
319 0x3605 CFDP_MetadataCantParseOptions 5 CFDP fsfw/src/fsfw/cfdp/definitions.h
320 0x3606 CFDP_NakCantParseOptions 6 CFDP fsfw/src/fsfw/cfdp/definitions.h
321 0x3607 CFDP_FinishedCantParseFsResponses 7 CFDP fsfw/src/fsfw/cfdp/definitions.h
322 0x3608 CFDP_FilestoreRequiresSecondFile 8 CFDP fsfw/src/fsfw/cfdp/definitions.h
323 0x3609 CFDP_FilestoreResponseCantParseFsMessage 9 CFDP fsfw/src/fsfw/cfdp/definitions.h
324 0x360a CFDP_InvalidPduFormat 10 CFDP fsfw/src/fsfw/cfdp/definitions.h
325 0x4300 FILS_GenericFileError 0 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
326 0x4301 FILS_GenericDirError 1 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
327 0x4302 FILS_FilesystemInactive 2 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
328 0x4303 FILS_GenericRenameError 3 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
329 0x4304 FILS_IsBusy 4 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
330 0x4305 FILS_InvalidParameters 5 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
331 0x430a FILS_FileDoesNotExist 10 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
332 0x430b FILS_FileAlreadyExists 11 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
333 0x430c FILS_NotAFile 12 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
334 0x430d FILS_FileLocked 13 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
335 0x430e FILS_PermissionDenied 14 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
336 0x4315 FILS_DirectoryDoesNotExist 21 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
337 0x4316 FILS_DirectoryAlreadyExists 22 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
338 0x4317 FILS_NotADirectory 23 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
339 0x4318 FILS_DirectoryNotEmpty 24 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
340 0x431e FILS_SequencePacketMissingWrite 30 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
341 0x431f FILS_SequencePacketMissingRead 31 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
342 0x2c01 CCS_BcIsSetVrCommand 1 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
343 0x2c02 CCS_BcIsUnlockCommand 2 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
344 0x2cb0 CCS_BcIllegalCommand 176 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
345 0x2cb1 CCS_BoardReadingNotFinished 177 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
346 0x2cf0 CCS_NsPositiveW 240 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
347 0x2cf1 CCS_NsNegativeW 241 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
348 0x2cf2 CCS_NsLockout 242 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
349 0x2cf3 CCS_FarmInLockout 243 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
350 0x2cf4 CCS_FarmInWait 244 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
351 0x2ce0 CCS_WrongSymbol 224 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
352 0x2ce1 CCS_DoubleStart 225 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
353 0x2ce2 CCS_StartSymbolMissed 226 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
354 0x2ce3 CCS_EndWithoutStart 227 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
355 0x2ce4 CCS_TooLarge 228 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
356 0x2ce5 CCS_TooShort 229 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
357 0x2ce6 CCS_WrongTfVersion 230 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
358 0x2ce7 CCS_WrongSpacecraftId 231 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
359 0x2ce8 CCS_NoValidFrameType 232 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
360 0x2ce9 CCS_CrcFailed 233 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
361 0x2cea CCS_VcNotFound 234 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
362 0x2ceb CCS_ForwardingFailed 235 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
363 0x2cec CCS_ContentTooLarge 236 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
364 0x2ced CCS_ResidualData 237 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
365 0x2cee CCS_DataCorrupted 238 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
366 0x2cef CCS_IllegalSegmentationFlag 239 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
367 0x2cd0 CCS_IllegalFlagCombination 208 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
368 0x2cd1 CCS_ShorterThanHeader 209 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
369 0x2cd2 CCS_TooShortBlockedPacket 210 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
370 0x2cd3 CCS_TooShortMapExtraction 211 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
371 0x430c 0x4201 FILS_NotAFile PUS11_InvalidTypeTimeWindow No description 12 1 FILE_SYSTEM PUS_SERVICE_11 fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
372 0x430d 0x4202 FILS_FileLocked PUS11_InvalidTimeWindow No description 13 2 FILE_SYSTEM PUS_SERVICE_11 fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
373 0x430e 0x4203 FILS_PermissionDenied PUS11_TimeshiftingNotPossible No description 14 3 FILE_SYSTEM PUS_SERVICE_11 fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
374 0x4315 0x4204 FILS_DirectoryDoesNotExist PUS11_InvalidRelativeTime No description 21 4 FILE_SYSTEM PUS_SERVICE_11 fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
375 0x4316 0x4205 FILS_DirectoryAlreadyExists PUS11_ContainedTcTooSmall No description 22 5 FILE_SYSTEM PUS_SERVICE_11 fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
376 0x4317 0x4206 FILS_NotADirectory PUS11_ContainedTcCrcMissmatch No description 23 6 FILE_SYSTEM PUS_SERVICE_11 fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
377 0x4318 0x3401 FILS_DirectoryNotEmpty DC_NoReplyReceived No description 24 1 FILE_SYSTEM DEVICE_COMMUNICATION_IF fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
378 0x431e 0x3402 FILS_SequencePacketMissingWrite DC_ProtocolError No description 30 2 FILE_SYSTEM DEVICE_COMMUNICATION_IF fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
379 0x431f 0x3403 FILS_SequencePacketMissingRead DC_Nullpointer No description 31 3 FILE_SYSTEM DEVICE_COMMUNICATION_IF fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
380 0x4201 0x3404 PUS11_InvalidTypeTimeWindow DC_InvalidCookieType No description 1 4 PUS_SERVICE_11 DEVICE_COMMUNICATION_IF fsfw/src/fsfw/pus/Service11TelecommandScheduling.h fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
381 0x4202 0x3405 PUS11_InvalidTimeWindow DC_NotActive No description 2 5 PUS_SERVICE_11 DEVICE_COMMUNICATION_IF fsfw/src/fsfw/pus/Service11TelecommandScheduling.h fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
382 0x4203 0x3406 PUS11_TimeshiftingNotPossible DC_TooMuchData No description 3 6 PUS_SERVICE_11 DEVICE_COMMUNICATION_IF fsfw/src/fsfw/pus/Service11TelecommandScheduling.h fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
0x4204 PUS11_InvalidRelativeTime No description 4 PUS_SERVICE_11 fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4205 PUS11_ContainedTcTooSmall No description 5 PUS_SERVICE_11 fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4206 PUS11_ContainedTcCrcMissmatch No description 6 PUS_SERVICE_11 fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4100 PUS9_ConnBroken No description 0 PUS_SERVICE_9 fsfw/src/fsfw/osal/common/TcpTmTcServer.h
0x2a01 IEC_NoConfigurationTable No description 1 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a02 IEC_NoCpuTable No description 2 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a03 IEC_InvalidWorkspaceAddress No description 3 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a04 IEC_TooLittleWorkspace No description 4 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a05 IEC_WorkspaceAllocation No description 5 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a06 IEC_InterruptStackTooSmall No description 6 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a07 IEC_ThreadExitted No description 7 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a08 IEC_InconsistentMpInformation No description 8 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a09 IEC_InvalidNode No description 9 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a0a IEC_NoMpci No description 10 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a0b IEC_BadPacket No description 11 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a0c IEC_OutOfPackets No description 12 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a0d IEC_OutOfGlobalObjects No description 13 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a0e IEC_OutOfProxies No description 14 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
383 0x2a0f 0x03a0 IEC_InvalidGlobalId DHB_InvalidChannel No description 15 160 INTERNAL_ERROR_CODES DEVICE_HANDLER_BASE fsfw/src/fsfw/osal/InternalErrorCodes.h fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
384 0x2a10 0x03b0 IEC_BadStackHook DHB_AperiodicReply No description 16 176 INTERNAL_ERROR_CODES DEVICE_HANDLER_BASE fsfw/src/fsfw/osal/InternalErrorCodes.h fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
385 0x2a11 0x03b1 IEC_BadAttributes DHB_IgnoreReplyData No description 17 177 INTERNAL_ERROR_CODES DEVICE_HANDLER_BASE fsfw/src/fsfw/osal/InternalErrorCodes.h fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
389 0x2a15 0x03d0 IEC_UnlimitedAndMaximumIs0 DHB_NoSwitch No description 21 208 INTERNAL_ERROR_CODES DEVICE_HANDLER_BASE fsfw/src/fsfw/osal/InternalErrorCodes.h fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
390 0x1401 0x03e0 SE_BufferTooShort DHB_ChildTimeout No description 1 224 SERIALIZE_IF DEVICE_HANDLER_BASE fsfw/src/fsfw/serialize/SerializeIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
391 0x1402 0x03e1 SE_StreamTooShort DHB_SwitchFailed No description 2 225 SERIALIZE_IF DEVICE_HANDLER_BASE fsfw/src/fsfw/serialize/SerializeIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
392 0x1403 0x1201 SE_TooManyElements AB_NeedSecondStep No description 3 1 SERIALIZE_IF ASSEMBLY_BASE fsfw/src/fsfw/serialize/SerializeIF.h fsfw/src/fsfw/devicehandlers/AssemblyBase.h
393 0x2600 0x1202 FDI_YourFault AB_NeedToReconfigure No description 0 2 HANDLES_FAILURES_IF ASSEMBLY_BASE fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h fsfw/src/fsfw/devicehandlers/AssemblyBase.h
394 0x2601 0x1203 FDI_MyFault AB_ModeFallback No description 1 3 HANDLES_FAILURES_IF ASSEMBLY_BASE fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h fsfw/src/fsfw/devicehandlers/AssemblyBase.h
395 0x2602 0x1204 FDI_ConfirmLater AB_ChildNotCommandable No description 2 4 HANDLES_FAILURES_IF ASSEMBLY_BASE fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h fsfw/src/fsfw/devicehandlers/AssemblyBase.h
396 0x2c01 0x1205 CCS_BcIsSetVrCommand AB_NeedToChangeHealth No description 1 5 CCSDS_HANDLER_IF ASSEMBLY_BASE fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/AssemblyBase.h
397 0x2c02 0x12a1 CCS_BcIsUnlockCommand AB_NotEnoughChildrenInCorrectState No description 2 161 CCSDS_HANDLER_IF ASSEMBLY_BASE fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/AssemblyBase.h
398 0x2cb0 0x27a0 CCS_BcIllegalCommand DHI_NoCommandData No description 176 160 CCSDS_HANDLER_IF DEVICE_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
399 0x2cb1 0x27a1 CCS_BoardReadingNotFinished DHI_CommandNotSupported No description 177 161 CCSDS_HANDLER_IF DEVICE_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
400 0x2cf0 0x27a2 CCS_NsPositiveW DHI_CommandAlreadySent No description 240 162 CCSDS_HANDLER_IF DEVICE_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
416 0x2ceb 0x27c3 CCS_ForwardingFailed DHI_DeviceReplyInvalid No description 235 195 CCSDS_HANDLER_IF DEVICE_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
417 0x2cec 0x27d0 CCS_ContentTooLarge DHI_InvalidCommandParameter No description 236 208 CCSDS_HANDLER_IF DEVICE_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
418 0x2ced 0x27d1 CCS_ResidualData DHI_InvalidNumberOrLengthOfParameters No description 237 209 CCSDS_HANDLER_IF DEVICE_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
419 0x2cee 0x2401 CCS_DataCorrupted MT_TooDetailedRequest No description 238 1 CCSDS_HANDLER_IF MATCH_TREE_CLASS fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
420 0x2cef 0x2402 CCS_IllegalSegmentationFlag MT_TooGeneralRequest No description 239 2 CCSDS_HANDLER_IF MATCH_TREE_CLASS fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
421 0x2cd0 0x2403 CCS_IllegalFlagCombination MT_NoMatch No description 208 3 CCSDS_HANDLER_IF MATCH_TREE_CLASS fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
422 0x2cd1 0x2404 CCS_ShorterThanHeader MT_Full No description 209 4 CCSDS_HANDLER_IF MATCH_TREE_CLASS fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
423 0x2cd2 0x2405 CCS_TooShortBlockedPacket MT_NewNodeCreated No description 210 5 CCSDS_HANDLER_IF MATCH_TREE_CLASS fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
424 0x2cd3 0x3f01 CCS_TooShortMapExtraction DLEE_NoPacketFound No description 211 1 CCSDS_HANDLER_IF DLE_ENCODER fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/globalfunctions/DleParser.h
425 0x4500 0x3f02 HSPI_OpeningFileFailed DLEE_PossiblePacketLoss No description 0 2 HAL_SPI DLE_ENCODER fsfw/src/fsfw_hal/linux/spi/SpiComIF.h fsfw/src/fsfw/globalfunctions/DleParser.h
426 0x4501 0x2f01 HSPI_FullDuplexTransferFailed ASC_TooLongForTargetType No description 1 HAL_SPI ASCII_CONVERTER fsfw/src/fsfw_hal/linux/spi/SpiComIF.h fsfw/src/fsfw/globalfunctions/AsciiConverter.h
427 0x4502 0x2f02 HSPI_HalfDuplexTransferFailed ASC_InvalidCharacters No description 2 HAL_SPI ASCII_CONVERTER fsfw/src/fsfw_hal/linux/spi/SpiComIF.h fsfw/src/fsfw/globalfunctions/AsciiConverter.h
428 0x4801 0x2f03 HGIO_UnknownGpioId ASC_BufferTooSmall No description 1 3 HAL_GPIO ASCII_CONVERTER fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/globalfunctions/AsciiConverter.h
429 0x4802 0x1701 HGIO_DriveGpioFailure HHI_ObjectNotHealthy No description 2 1 HAL_GPIO HAS_HEALTH_IF fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/health/HasHealthIF.h
430 0x4803 0x1702 HGIO_GpioTypeFailure HHI_InvalidHealthState No description 3 2 HAL_GPIO HAS_HEALTH_IF fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/health/HasHealthIF.h
431 0x4804 0x1703 HGIO_GpioInvalidInstance HHI_IsExternallyControlled No description 4 3 HAL_GPIO HAS_HEALTH_IF fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/health/HasHealthIF.h
432 0x4805 0x3201 HGIO_GpioDuplicateDetected CF_ObjectHasNoFunctions No description 5 1 HAL_GPIO COMMANDS_ACTIONS_IF fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/action/CommandsActionsIF.h
433 0x4806 0x3202 HGIO_GpioInitFailed CF_AlreadyCommanding No description 6 2 HAL_GPIO COMMANDS_ACTIONS_IF fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/action/CommandsActionsIF.h
434 0x4807 0x3301 HGIO_GpioGetValueFailed HF_IsBusy No description 7 1 HAL_GPIO HAS_ACTIONS_IF fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/action/HasActionsIF.h
435 0x4601 0x3302 HURT_UartReadFailure HF_InvalidParameters No description 1 2 HAL_UART HAS_ACTIONS_IF fsfw/src/fsfw_hal/linux/serial/SerialComIF.h fsfw/src/fsfw/action/HasActionsIF.h
436 0x4602 0x3303 HURT_UartReadSizeMissmatch HF_ExecutionFinished No description 2 3 HAL_UART HAS_ACTIONS_IF fsfw/src/fsfw_hal/linux/serial/SerialComIF.h fsfw/src/fsfw/action/HasActionsIF.h
437 0x4603 0x3304 HURT_UartRxBufferTooSmall HF_InvalidActionId No description 3 4 HAL_UART HAS_ACTIONS_IF fsfw/src/fsfw_hal/linux/serial/SerialComIF.h fsfw/src/fsfw/action/HasActionsIF.h
438 0x4400 0x1000 UXOS_ExecutionFinished TIM_UnsupportedTimeFormat Execution of the current command has finished 0 LINUX_OSAL CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw_hal/linux/CommandExecutor.h fsfw/src/fsfw/timemanager/CCSDSTime.h
439 0x4401 0x1001 UXOS_CommandPending TIM_NotEnoughInformationForTargetFormat 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 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw_hal/linux/CommandExecutor.h fsfw/src/fsfw/timemanager/CCSDSTime.h
440 0x4402 0x1002 UXOS_BytesRead TIM_LengthMismatch Some bytes have been read from the executing process 2 LINUX_OSAL CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw_hal/linux/CommandExecutor.h fsfw/src/fsfw/timemanager/CCSDSTime.h
441 0x1003 TIM_InvalidTimeFormat 3 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
442 0x1004 TIM_InvalidDayOfYear 4 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
443 0x1005 TIM_TimeDoesNotFitFormat 5 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
444 0x3701 TSI_BadTimestamp 1 TIME_STAMPER_IF fsfw/src/fsfw/timemanager/TimeStampIF.h
445 0x3c00 LPIF_PoolEntryNotFound 0 LOCAL_POOL_OWNER_IF fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h
446 0x3c01 LPIF_PoolEntryTypeConflict 1 LOCAL_POOL_OWNER_IF fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h
447 0x3e00 HKM_QueueOrDestinationInvalid 0 HOUSEKEEPING_MANAGER fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
448 0x3e01 HKM_WrongHkPacketType 1 HOUSEKEEPING_MANAGER fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
449 0x3e02 HKM_ReportingStatusUnchanged 2 HOUSEKEEPING_MANAGER fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
450 0x3e03 HKM_PeriodicHelperInvalid 3 HOUSEKEEPING_MANAGER fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
451 0x3e04 HKM_PoolobjectNotFound 4 HOUSEKEEPING_MANAGER fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
452 0x3e05 HKM_DatasetNotFound 5 HOUSEKEEPING_MANAGER fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
453 0x2901 TC_InvalidTargetState 1 THERMAL_COMPONENT_IF fsfw/src/fsfw/thermal/ThermalComponentIF.h
454 0x29f1 TC_AboveOperationalLimit 241 THERMAL_COMPONENT_IF fsfw/src/fsfw/thermal/ThermalComponentIF.h
455 0x29f2 TC_BelowOperationalLimit 242 THERMAL_COMPONENT_IF fsfw/src/fsfw/thermal/ThermalComponentIF.h
456 0x2001 CSB_ExecutionComplete 1 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
457 0x2002 CSB_NoStepMessage 2 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
458 0x2003 CSB_ObjectBusy 3 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
459 0x2004 CSB_Busy 4 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
460 0x2005 CSB_InvalidTc 5 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
461 0x2006 CSB_InvalidObject 6 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
462 0x2007 CSB_InvalidReply 7 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
463 0x4c00 SPPA_NoPacketFound 0 SPACE_PACKET_PARSER fsfw/src/fsfw/tmtcservices/SpacePacketParser.h
464 0x4c01 SPPA_SplitPacket 1 SPACE_PACKET_PARSER fsfw/src/fsfw/tmtcservices/SpacePacketParser.h
465 0x1d01 ATC_ActivityStarted 1 ACCEPTS_TELECOMMANDS_IF fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h
466 0x1d02 ATC_InvalidSubservice 2 ACCEPTS_TELECOMMANDS_IF fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h
467 0x1d03 ATC_IllegalApplicationData 3 ACCEPTS_TELECOMMANDS_IF fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h
468 0x1d04 ATC_SendTmFailed 4 ACCEPTS_TELECOMMANDS_IF fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h
469 0x1d05 ATC_Timeout 5 ACCEPTS_TELECOMMANDS_IF fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h

View File

@ -121,8 +121,8 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path
11706;0x2dba;SELF_TEST_MTM_RANGE_FAILURE;LOW;Get self test result returns failure that MTM values were outside of the expected range. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;mission/devices/ImtqHandler.h 11706;0x2dba;SELF_TEST_MTM_RANGE_FAILURE;LOW;Get self test result returns failure that MTM values were outside of the expected range. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;mission/devices/ImtqHandler.h
11707;0x2dbb;SELF_TEST_COIL_CURRENT_FAILURE;LOW;Get self test result returns failure indicating that the coil current was outside of the expected range P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;mission/devices/ImtqHandler.h 11707;0x2dbb;SELF_TEST_COIL_CURRENT_FAILURE;LOW;Get self test result returns failure indicating that the coil current was outside of the expected range P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA;mission/devices/ImtqHandler.h
11708;0x2dbc;INVALID_ERROR_BYTE;LOW;Received invalid error byte. This indicates an error of the communication link between IMTQ and OBC.;mission/devices/ImtqHandler.h 11708;0x2dbc;INVALID_ERROR_BYTE;LOW;Received invalid error byte. This indicates an error of the communication link between IMTQ and OBC.;mission/devices/ImtqHandler.h
11801;0x2e19;ERROR_STATE;HIGH;Reaction wheel signals an error state;mission/devices/devicedefinitions/RwDefinitions.h 11801;0x2e19;ERROR_STATE;HIGH;Reaction wheel signals an error state;mission/devices/devicedefinitions/rwHelpers.h
11802;0x2e1a;RESET_OCCURED;LOW;;mission/devices/devicedefinitions/RwDefinitions.h 11802;0x2e1a;RESET_OCCURED;LOW;;mission/devices/devicedefinitions/rwHelpers.h
11901;0x2e7d;BOOTING_FIRMWARE_FAILED;LOW;Failed to boot firmware;linux/devices/startracker/StarTrackerHandler.h 11901;0x2e7d;BOOTING_FIRMWARE_FAILED;LOW;Failed to boot firmware;linux/devices/startracker/StarTrackerHandler.h
11902;0x2e7e;BOOTING_BOOTLOADER_FAILED;LOW;Failed to boot star tracker into bootloader mode;linux/devices/startracker/StarTrackerHandler.h 11902;0x2e7e;BOOTING_BOOTLOADER_FAILED;LOW;Failed to boot star tracker into bootloader mode;linux/devices/startracker/StarTrackerHandler.h
12001;0x2ee1;SUPV_MEMORY_READ_RPT_CRC_FAILURE;LOW;PLOC supervisor crc failure in telemetry packet;linux/devices/ploc/PlocSupervisorHandler.h 12001;0x2ee1;SUPV_MEMORY_READ_RPT_CRC_FAILURE;LOW;PLOC supervisor crc failure in telemetry packet;linux/devices/ploc/PlocSupervisorHandler.h

1 Event ID (dec) Event ID (hex) Name Severity Description File Path
121 11703 11706 0x2db7 0x2dba SELF_TEST_ADC_FAILURE SELF_TEST_MTM_RANGE_FAILURE LOW Get self test result returns failure in measurement of current and temperature. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA Get self test result returns failure that MTM values were outside of the expected range. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA mission/devices/ImtqHandler.h
122 11704 11707 0x2db8 0x2dbb SELF_TEST_PWM_FAILURE SELF_TEST_COIL_CURRENT_FAILURE LOW Get self test result returns PWM failure which concerns the coil actuation. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA Get self test result returns failure indicating that the coil current was outside of the expected range P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA mission/devices/ImtqHandler.h
123 11705 11708 0x2db9 0x2dbc SELF_TEST_TC_FAILURE INVALID_ERROR_BYTE LOW Get self test result returns TC failure (system failure) P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA Received invalid error byte. This indicates an error of the communication link between IMTQ and OBC. mission/devices/ImtqHandler.h
124 11706 11801 0x2dba 0x2e19 SELF_TEST_MTM_RANGE_FAILURE ERROR_STATE LOW HIGH Get self test result returns failure that MTM values were outside of the expected range. P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA Reaction wheel signals an error state mission/devices/ImtqHandler.h mission/devices/devicedefinitions/rwHelpers.h
125 11707 11802 0x2dbb 0x2e1a SELF_TEST_COIL_CURRENT_FAILURE RESET_OCCURED LOW Get self test result returns failure indicating that the coil current was outside of the expected range P1: Indicates on which axis the failure occurred. 0 -> INIT, 1 -> +X, 2 -> -X, 3 -> +Y, 4 -> -Y, 5 -> +Z, 6 -> -Z, 7 -> FINA mission/devices/ImtqHandler.h mission/devices/devicedefinitions/rwHelpers.h
126 11708 11901 0x2dbc 0x2e7d INVALID_ERROR_BYTE BOOTING_FIRMWARE_FAILED LOW Received invalid error byte. This indicates an error of the communication link between IMTQ and OBC. Failed to boot firmware mission/devices/ImtqHandler.h linux/devices/startracker/StarTrackerHandler.h
127 11801 11902 0x2e19 0x2e7e ERROR_STATE BOOTING_BOOTLOADER_FAILED HIGH LOW Reaction wheel signals an error state Failed to boot star tracker into bootloader mode mission/devices/devicedefinitions/rwHelpers.h linux/devices/startracker/StarTrackerHandler.h
128 11802 12001 0x2e1a 0x2ee1 RESET_OCCURED SUPV_MEMORY_READ_RPT_CRC_FAILURE LOW No description PLOC supervisor crc failure in telemetry packet mission/devices/devicedefinitions/rwHelpers.h linux/devices/ploc/PlocSupervisorHandler.h

View File

@ -76,7 +76,7 @@
0x49010005;GPIO_IF 0x49010005;GPIO_IF
0x49010006;SCEX_UART_READER 0x49010006;SCEX_UART_READER
0x49020004;SPI_MAIN_COM_IF 0x49020004;SPI_MAIN_COM_IF
0x49020005;SPI_RW_COM_IF 0x49020005;RW_POLLING_TASK
0x49020006;SPI_RTD_COM_IF 0x49020006;SPI_RTD_COM_IF
0x49030003;UART_COM_IF 0x49030003;UART_COM_IF
0x49040002;I2C_COM_IF 0x49040002;I2C_COM_IF

1 0x00005060 P60DOCK_TEST_TASK
76 0x49000000 0x49010005 ARDUINO_COM_IF GPIO_IF
77 0x49010005 0x49010006 GPIO_IF SCEX_UART_READER
78 0x49010006 0x49020004 SCEX_UART_READER SPI_MAIN_COM_IF
79 0x49020004 0x49020005 SPI_MAIN_COM_IF RW_POLLING_TASK
80 0x49020005 0x49020006 RW_POLLING_TASK SPI_RTD_COM_IF
81 0x49020006 0x49030003 SPI_RTD_COM_IF UART_COM_IF
82 0x49030003 0x49040002 UART_COM_IF I2C_COM_IF

View File

@ -1,38 +1,29 @@
Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x0000;OK;System-wide code for ok.;0;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h 0x0000;OK;System-wide code for ok.;0;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h
0x0001;Failed;Unspecified system-wide code for failed.;1;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h 0x0001;Failed;Unspecified system-wide code for failed.;1;HasReturnvaluesIF;fsfw/returnvalues/returnvalue.h
0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h 0x63a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NVMParameterBase.h
0x5d00;GOMS_PacketTooLong;;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x6300;NVMB_Busy;;0;NVM_PARAM_BASE;mission/system/objects/Stack5VHandler.h
0x5d01;GOMS_InvalidTableId;;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x52b0;RWHA_SpiWriteFailure;;176;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.h
0x5d02;GOMS_InvalidAddress;;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x52b1;RWHA_SpiReadFailure;Used by the spi send function to tell a failing read call;177;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.h
0x5d03;GOMS_InvalidParamSize;;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.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/devicedefinitions/rwHelpers.h
0x5d04;GOMS_InvalidPayloadSize;;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x52b3;RWHA_InvalidSubstitute;Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination;179;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.h
0x5d05;GOMS_UnknownReplyId;;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x52b4;RWHA_MissingEndSign;HDLC decoding mechanism never receives the end sign 0x7E;180;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.h
0x52b0;RWHA_SpiWriteFailure;;176;RW_HANDLER;mission/devices/RwHandler.h 0x52b5;RWHA_NoReply;Reaction wheel only responds with empty frames.;181;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.h
0x52b1;RWHA_SpiReadFailure;Used by the spi send function to tell a failing read call;177;RW_HANDLER;mission/devices/RwHandler.h 0x52b6;RWHA_NoStartMarker;Expected a start marker as first byte;182;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.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 0x52b7;RWHA_SpiReadTimeout;Timeout when reading reply;183;RW_HANDLER;mission/devices/devicedefinitions/rwHelpers.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
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 0x58a0;SUSS_ErrorUnlockMutex;;160;SUS_HANDLER;mission/devices/SusHandler.h
0x58a1;SUSS_ErrorLockMutex;;161;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 0x66a0;SADPL_CommandNotSupported;;160;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
0x51a1;IMTQ_ParameterMissing;;161;IMTQ_HANDLER;mission/devices/ImtqHandler.h 0x66a1;SADPL_DeploymentAlreadyExecuting;;161;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
0x51a2;IMTQ_ParameterInvalid;;162;IMTQ_HANDLER;mission/devices/ImtqHandler.h 0x66a2;SADPL_MainSwitchTimeoutFailure;;162;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
0x51a3;IMTQ_CcUnavailable;;163;IMTQ_HANDLER;mission/devices/ImtqHandler.h 0x66a3;SADPL_SwitchingDeplSa1Failed;;163;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
0x51a4;IMTQ_InternalProcessingError;;164;IMTQ_HANDLER;mission/devices/ImtqHandler.h 0x66a4;SADPL_SwitchingDeplSa2Failed;;164;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h
0x51a5;IMTQ_RejectedWithoutReason;;165;IMTQ_HANDLER;mission/devices/ImtqHandler.h 0x51a0;IMTQ_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;IMTQ_HANDLER;mission/devices/RwHandler.h
0x51a1;IMTQ_InvalidRampTime;Action Message with invalid ramp time was received.;161;IMTQ_HANDLER;mission/devices/RwHandler.h
0x51a2;IMTQ_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;IMTQ_HANDLER;mission/devices/RwHandler.h
0x51a3;IMTQ_ExecutionFailed;Command execution failed;163;IMTQ_HANDLER;mission/devices/RwHandler.h
0x51a4;IMTQ_CrcError;Reaction wheel reply has invalid crc;164;IMTQ_HANDLER;mission/devices/RwHandler.h
0x51a5;IMTQ_ValueNotRead;;165;IMTQ_HANDLER;mission/devices/RwHandler.h
0x51a6;IMTQ_CmdErrUnknown;;166;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 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/SyrlinksHandler.h 0x50a0;SYRLINKS_CrcFailure;;160;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h
@ -44,137 +35,123 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x50a6;SYRLINKS_BadCrcAck;;166;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a6;SYRLINKS_BadCrcAck;;166;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h
0x50a7;SYRLINKS_ReplyWrongSize;;167;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a7;SYRLINKS_ReplyWrongSize;;167;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h
0x50a8;SYRLINKS_MissingStartFrameCharacter;;168;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h 0x50a8;SYRLINKS_MissingStartFrameCharacter;;168;SYRLINKS_HANDLER;mission/devices/SyrlinksHandler.h
0x66a0;SADPL_CommandNotSupported;;160;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h 0x5d00;GOMS_PacketTooLong;;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x66a1;SADPL_DeploymentAlreadyExecuting;;161;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h 0x5d01;GOMS_InvalidTableId;;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x66a2;SADPL_MainSwitchTimeoutFailure;;162;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h 0x5d02;GOMS_InvalidAddress;;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x66a3;SADPL_SwitchingDeplSa1Failed;;163;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h 0x5d03;GOMS_InvalidParamSize;;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x66a4;SADPL_SwitchingDeplSa2Failed;;164;SA_DEPL_HANDLER;mission/devices/SolarArrayDeploymentHandler.h 0x5d04;GOMS_InvalidPayloadSize;;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x6600;SADPL_Busy;;0;SA_DEPL_HANDLER;mission/system/objects/Stack5VHandler.h 0x5d05;GOMS_UnknownReplyId;;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x6b01;ACSPTG_PtgctrlMekfInputInvalid;;1;ACS_PTG;mission/controller/acs/control/PtgCtrl.h 0x4fa1;HEATER_CommandNotSupported;;161;HEATER_HANDLER;mission/devices/HeaterHandler.h
0x4fa2;HEATER_InitFailed;;162;HEATER_HANDLER;mission/devices/HeaterHandler.h
0x4fa3;HEATER_InvalidSwitchNr;;163;HEATER_HANDLER;mission/devices/HeaterHandler.h
0x4fa4;HEATER_MainSwitchSetTimeout;;164;HEATER_HANDLER;mission/devices/HeaterHandler.h
0x4fa5;HEATER_CommandAlreadyWaiting;;165;HEATER_HANDLER;mission/devices/HeaterHandler.h
0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h
0x6a01;ACSSAF_SafectrlMekfInputInvalid;;1;ACS_SAFE;mission/controller/acs/control/SafeCtrl.h 0x6a01;ACSSAF_SafectrlMekfInputInvalid;;1;ACS_SAFE;mission/controller/acs/control/SafeCtrl.h
0x6b01;ACSPTG_PtgctrlMekfInputInvalid;;1;ACS_PTG;mission/controller/acs/control/PtgCtrl.h
0x6c01;ACSDTB_DetumbleNoSensordata;;1;ACS_DETUMBLE;mission/controller/acs/control/Detumble.h 0x6c01;ACSDTB_DetumbleNoSensordata;;1;ACS_DETUMBLE;mission/controller/acs/control/Detumble.h
0x6901;ACSKAL_KalmanNoGyrMeas;;1;ACS_KALMAN;mission/controller/acs/MultiplicativeKalmanFilter.h 0x6901;ACSKAL_KalmanNoGyrMeas;;1;ACS_KALMAN;mission/controller/acs/MultiplicativeKalmanFilter.h
0x6902;ACSKAL_KalmanNoModel;;2;ACS_KALMAN;mission/controller/acs/MultiplicativeKalmanFilter.h 0x6902;ACSKAL_KalmanNoModel;;2;ACS_KALMAN;mission/controller/acs/MultiplicativeKalmanFilter.h
0x6903;ACSKAL_KalmanInversionFailed;;3;ACS_KALMAN;mission/controller/acs/MultiplicativeKalmanFilter.h 0x6903;ACSKAL_KalmanInversionFailed;;3;ACS_KALMAN;mission/controller/acs/MultiplicativeKalmanFilter.h
0x63a0;NVMB_KeyNotExists;Specified key does not exist in json file;160;NVM_PARAM_BASE;mission/memory/NVMParameterBase.h 0x4500;HSPI_OpeningFileFailed;;0;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
0x2c01;CCS_BcIsSetVrCommand;;1;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4501;HSPI_FullDuplexTransferFailed;;1;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
0x2c02;CCS_BcIsUnlockCommand;;2;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4502;HSPI_HalfDuplexTransferFailed;;2;HAL_SPI;fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
0x2cb0;CCS_BcIllegalCommand;;176;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4801;HGIO_UnknownGpioId;;1;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2cb1;CCS_BoardReadingNotFinished;;177;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4802;HGIO_DriveGpioFailure;;2;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2cf0;CCS_NsPositiveW;;240;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4803;HGIO_GpioTypeFailure;;3;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2cf1;CCS_NsNegativeW;;241;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4804;HGIO_GpioInvalidInstance;;4;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2cf2;CCS_NsLockout;;242;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4805;HGIO_GpioDuplicateDetected;;5;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2cf3;CCS_FarmInLockout;;243;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4806;HGIO_GpioInitFailed;;6;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2cf4;CCS_FarmInWait;;244;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4807;HGIO_GpioGetValueFailed;;7;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
0x2ce0;CCS_WrongSymbol;;224;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4601;HURT_UartReadFailure;;1;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
0x2ce1;CCS_DoubleStart;;225;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4602;HURT_UartReadSizeMissmatch;;2;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
0x2ce2;CCS_StartSymbolMissed;;226;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4603;HURT_UartRxBufferTooSmall;;3;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
0x2ce3;CCS_EndWithoutStart;;227;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4400;UXOS_ExecutionFinished;Execution of the current command has finished;0;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
0x2ce4;CCS_TooLarge;;228;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.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
0x2ce5;CCS_TooShort;;229;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4402;UXOS_BytesRead;Some bytes have been read from the executing process;2;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
0x2ce6;CCS_WrongTfVersion;;230;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4403;UXOS_CommandError;Command execution failed;3;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
0x2ce7;CCS_WrongSpacecraftId;;231;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4404;UXOS_NoCommandLoadedOrPending;;4;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
0x2ce8;CCS_NoValidFrameType;;232;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x4406;UXOS_PcloseCallError;;6;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h
0x2ce9;CCS_CrcFailed;;233;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x2801;SM_DataTooLarge;;1;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2cea;CCS_VcNotFound;;234;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x2802;SM_DataStorageFull;;2;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2ceb;CCS_ForwardingFailed;;235;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x2803;SM_IllegalStorageId;;3;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2cec;CCS_ContentTooLarge;;236;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x2804;SM_DataDoesNotExist;;4;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2ced;CCS_ResidualData;;237;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x2805;SM_IllegalAddress;;5;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2cee;CCS_DataCorrupted;;238;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x2806;SM_PoolTooLarge;;6;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2cef;CCS_IllegalSegmentationFlag;;239;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x0601;PP_DoItMyself;;1;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2cd0;CCS_IllegalFlagCombination;;208;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x0602;PP_PointsToVariable;;2;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2cd1;CCS_ShorterThanHeader;;209;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x0603;PP_PointsToMemory;;3;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2cd2;CCS_TooShortBlockedPacket;;210;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x0604;PP_ActivityCompleted;;4;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2cd3;CCS_TooShortMapExtraction;;211;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h 0x0605;PP_PointsToVectorUint8;;5;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x3b00;SPH_ConnBroken;;0;SEMAPHORE_IF;fsfw/src/fsfw/osal/common/TcpTmTcServer.h 0x0606;PP_PointsToVectorUint16;;6;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a01;IEC_NoConfigurationTable;;1;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x0607;PP_PointsToVectorUint32;;7;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a02;IEC_NoCpuTable;;2;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x0608;PP_PointsToVectorFloat;;8;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a03;IEC_InvalidWorkspaceAddress;;3;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x06a0;PP_DumpNotSupported;;160;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a04;IEC_TooLittleWorkspace;;4;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x06e0;PP_InvalidSize;;224;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a05;IEC_WorkspaceAllocation;;5;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x06e1;PP_InvalidAddress;;225;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a06;IEC_InterruptStackTooSmall;;6;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x06e2;PP_InvalidContent;;226;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a07;IEC_ThreadExitted;;7;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x06e3;PP_UnalignedAccess;;227;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a08;IEC_InconsistentMpInformation;;8;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x06e4;PP_WriteProtected;;228;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h
0x2a09;IEC_InvalidNode;;9;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x13e0;MH_UnknownCmd;;224;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h
0x2a0a;IEC_NoMpci;;10;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x13e1;MH_InvalidAddress;;225;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h
0x2a0b;IEC_BadPacket;;11;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x13e2;MH_InvalidSize;;226;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h
0x2a0c;IEC_OutOfPackets;;12;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x13e3;MH_StateMismatch;;227;MEMORY_HELPER;fsfw/src/fsfw/memory/MemoryHelper.h
0x2a0d;IEC_OutOfGlobalObjects;;13;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38a1;SGP4_InvalidEccentricity;;161;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a0e;IEC_OutOfProxies;;14;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38a2;SGP4_InvalidMeanMotion;;162;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a0f;IEC_InvalidGlobalId;;15;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38a3;SGP4_InvalidPerturbationElements;;163;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a10;IEC_BadStackHook;;16;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38a4;SGP4_InvalidSemiLatusRectum;;164;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a11;IEC_BadAttributes;;17;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38a5;SGP4_InvalidEpochElements;;165;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a12;IEC_ImplementationKeyCreateInconsistency;;18;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38a6;SGP4_SatelliteHasDecayed;;166;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a13;IEC_ImplementationBlockingOperationCancel;;19;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38b1;SGP4_TleTooOld;;177;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a14;IEC_MutexObtainFromBadState;;20;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h 0x38b2;SGP4_TleNotInitialized;;178;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2a15;IEC_UnlimitedAndMaximumIs0;;21;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.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 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 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 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 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 0x0c02;MS_InvalidEntry;;2;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
0x2e02;HPA_InvalidDomainId;;2;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h 0x0c03;MS_TooManyElements;;3;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
0x2e03;HPA_InvalidValue;;3;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h 0x0c04;MS_CantStoreEmpty;;4;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
0x2e05;HPA_ReadOnly;;5;HAS_PARAMETERS_IF;fsfw/src/fsfw/parameters/HasParametersIF.h 0x0b01;SB_ChildNotFound;;1;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x2d01;PAW_UnknownDatatype;;1;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0b02;SB_ChildInfoUpdated;;2;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x2d02;PAW_DatatypeMissmatch;;2;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0b03;SB_ChildDoesntHaveModes;;3;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x2d03;PAW_Readonly;;3;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0b04;SB_CouldNotInsertChild;;4;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x2d04;PAW_TooBig;;4;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0b05;SB_TableContainsInvalidObjectId;;5;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x2d05;PAW_SourceNotSet;;5;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0d01;SS_SequenceAlreadyExists;;1;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x2d06;PAW_OutOfBounds;;6;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0d02;SS_TableAlreadyExists;;2;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x2d07;PAW_NotSet;;7;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0d03;SS_TableDoesNotExist;;3;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x2d08;PAW_ColumnOrRowsZero;;8;PARAMETER_WRAPPER;fsfw/src/fsfw/parameters/ParameterWrapper.h 0x0d04;SS_TableOrSequenceLengthInvalid;;4;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x3201;CF_ObjectHasNoFunctions;;1;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h 0x0d05;SS_SequenceDoesNotExist;;5;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x3202;CF_AlreadyCommanding;;2;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h 0x0d06;SS_TableContainsInvalidObjectId;;6;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x3301;HF_IsBusy;;1;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h 0x0d07;SS_FallbackSequenceDoesNotExist;;7;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x3302;HF_InvalidParameters;;2;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h 0x0d08;SS_NoTargetTable;;8;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x3303;HF_ExecutionFinished;;3;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h 0x0d09;SS_SequenceOrTableTooLong;;9;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x3304;HF_InvalidActionId;;4;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h 0x0d0b;SS_IsFallbackSequence;;11;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0201;OM_InsertionFailed;;1;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h 0x0d0c;SS_AccessDenied;;12;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0202;OM_NotFound;;2;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h 0x0d0e;SS_TableInUse;;14;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0203;OM_ChildInitFailed;;3;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h 0x0da1;SS_TargetTableNotReached;;161;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0204;OM_InternalErrReporterUninit;;4;OBJECT_MANAGER_IF;fsfw/src/fsfw/objectmanager/ObjectManagerIF.h 0x0da2;SS_TableCheckFailed;;162;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x2600;FDI_YourFault;;0;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h 0x2501;EV_ListenerNotFound;;1;EVENT_MANAGER_IF;fsfw/src/fsfw/events/EventManagerIF.h
0x2601;FDI_MyFault;;1;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h
0x2602;FDI_ConfirmLater;;2;HANDLES_FAILURES_IF;fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h
0x2201;TMF_Busy;;1;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2202;TMF_LastPacketFound;;2;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2203;TMF_StopFetch;;3;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2204;TMF_Timeout;;4;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2205;TMF_TmChannelFull;;5;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2206;TMF_NotStored;;6;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2207;TMF_AllDeleted;;7;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2208;TMF_InvalidData;;8;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2209;TMF_NotReady;;9;TM_STORE_FRONTEND_IF;fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2101;TMB_Busy;;1;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2102;TMB_Full;;2;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2103;TMB_Empty;;3;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2104;TMB_NullRequested;;4;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2105;TMB_TooLarge;;5;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2106;TMB_NotReady;;6;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2107;TMB_DumpError;;7;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2108;TMB_CrcError;;8;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2109;TMB_Timeout;;9;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210a;TMB_IdlePacketFound;;10;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210b;TMB_TelecommandFound;;11;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210c;TMB_NoPusATm;;12;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210d;TMB_TooSmall;;13;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210e;TMB_BlockNotFound;;14;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210f;TMB_InvalidRequest;;15;TM_STORE_BACKEND_IF;fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x1c01;TCD_PacketLost;;1;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1c02;TCD_DestinationNotFound;;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1c03;TCD_ServiceIdAlreadyExists;;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1b00;TCC_NoDestinationFound;;0;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b01;TCC_InvalidCcsdsVersion;;1;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b02;TCC_InvalidApid;;2;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b03;TCC_InvalidPacketType;;3;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b04;TCC_InvalidSecHeaderField;;4;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b05;TCC_IncorrectPrimaryHeader;;5;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b07;TCC_IncompletePacket;;7;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b08;TCC_InvalidPusVersion;;8;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b09;TCC_IncorrectChecksum;;9;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b0a;TCC_IllegalPacketSubtype;;10;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1b0b;TCC_IncorrectSecondaryHeader;;11;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x04e1;RMP_CommandNoDescriptorsAvailable;;225;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x04e1;RMP_CommandNoDescriptorsAvailable;;225;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h
0x04e2;RMP_CommandBufferFull;;226;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 0x04e3;RMP_CommandChannelOutOfRange;;227;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h
@ -215,95 +192,9 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x040a;RMP_ReplyCommandNotImplementedOrNotAuthorised;;10;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h 0x040a;RMP_ReplyCommandNotImplementedOrNotAuthorised;;10;RMAP_CHANNEL;fsfw/src/fsfw/rmap/RMAP.h
0x040b;RMP_ReplyRmwDataLengthError;;11;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 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 0x1401;SE_BufferTooShort;;1;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h
0x2802;SM_DataStorageFull;;2;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h 0x1402;SE_StreamTooShort;;2;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h
0x2803;SM_IllegalStorageId;;3;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h 0x1403;SE_TooManyElements;;3;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h
0x2804;SM_DataDoesNotExist;;4;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2805;SM_IllegalAddress;;5;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x2806;SM_PoolTooLarge;;6;STORAGE_MANAGER_IF;fsfw/src/fsfw/storagemanager/StorageManagerIF.h
0x38a1;SGP4_InvalidEccentricity;;161;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38a2;SGP4_InvalidMeanMotion;;162;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38a3;SGP4_InvalidPerturbationElements;;163;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38a4;SGP4_InvalidSemiLatusRectum;;164;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38a5;SGP4_InvalidEpochElements;;165;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38a6;SGP4_SatelliteHasDecayed;;166;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38b1;SGP4_TleTooOld;;177;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x38b2;SGP4_TleNotInitialized;;178;SGP4PROPAGATOR_CLASS;fsfw/src/fsfw/coordinates/Sgp4Propagator.h
0x2401;MT_NoPacketFound;;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h
0x2402;MT_PossiblePacketLoss;;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/DleParser.h
0x2403;MT_NoMatch;;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x2404;MT_Full;;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x2405;MT_NewNodeCreated;;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x3f01;DLEE_StreamTooShort;;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h
0x3f02;DLEE_DecodingError;;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleEncoder.h
0x2f01;ASC_TooLongForTargetType;;1;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x2f02;ASC_InvalidCharacters;;2;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x2f03;ASC_BufferTooSmall;;3;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x0f01;CM_UnknownCommand;;1;COMMAND_MESSAGE;fsfw/src/fsfw/ipc/CommandMessageIF.h
0x3a01;MQI_Empty;;1;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h
0x3a02;MQI_Full;No space left for more messages;2;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h
0x3a03;MQI_NoReplyPartner;Returned if a reply method was called without partner;3;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h
0x3a04;MQI_DestinationInvalid;Returned if the target destination is invalid.;4;MESSAGE_QUEUE_IF;fsfw/src/fsfw/ipc/MessageQueueIF.h
0x3901;MUX_NotEnoughResources;;1;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3902;MUX_InsufficientMemory;;2;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3903;MUX_NoPrivilege;;3;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3904;MUX_WrongAttributeSetting;;4;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3905;MUX_MutexAlreadyLocked;;5;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3906;MUX_MutexNotFound;;6;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3907;MUX_MutexMaxLocks;;7;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3908;MUX_CurrThreadAlreadyOwnsMutex;;8;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3909;MUX_CurrThreadDoesNotOwnMutex;;9;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x390a;MUX_MutexTimeout;;10;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x390b;MUX_MutexInvalidId;;11;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x390c;MUX_MutexDestroyedWhileWaiting;;12;MUTEX_IF;fsfw/src/fsfw/ipc/MutexIF.h
0x3b01;SPH_SemaphoreTimeout;;1;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h
0x3b02;SPH_SemaphoreNotOwned;;2;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h
0x3b03;SPH_SemaphoreInvalid;;3;SEMAPHORE_IF;fsfw/src/fsfw/tasks/SemaphoreIF.h
0x1e00;PUS_InvalidPusVersion;;0;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h
0x1e01;PUS_InvalidCrc16;;1;PUS_IF;fsfw/src/fsfw/tmtcpacket/pus/PusIF.h
0x3601;CFDP_InvalidTlvType;;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3602;CFDP_InvalidDirectiveField;;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3603;CFDP_InvalidPduDatafieldLen;;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3604;CFDP_InvalidAckDirectiveFields;;4;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3605;CFDP_MetadataCantParseOptions;;5;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3606;CFDP_NakCantParseOptions;;6;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3607;CFDP_FinishedCantParseFsResponses;;7;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3608;CFDP_FilestoreRequiresSecondFile;;8;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3609;CFDP_FilestoreResponseCantParseFsMessage;;9;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x360a;CFDP_InvalidPduFormat;;10;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x2901;TC_InvalidTargetState;;1;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h
0x29f1;TC_AboveOperationalLimit;;241;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h
0x29f2;TC_BelowOperationalLimit;;242;THERMAL_COMPONENT_IF;fsfw/src/fsfw/thermal/ThermalComponentIF.h
0x0c02;MS_InvalidEntry;;2;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
0x0c03;MS_TooManyElements;;3;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
0x0c04;MS_CantStoreEmpty;;4;MODE_STORE_IF;fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
0x0d01;SS_SequenceAlreadyExists;;1;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d02;SS_TableAlreadyExists;;2;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d03;SS_TableDoesNotExist;;3;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d04;SS_TableOrSequenceLengthInvalid;;4;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d05;SS_SequenceDoesNotExist;;5;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d06;SS_TableContainsInvalidObjectId;;6;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d07;SS_FallbackSequenceDoesNotExist;;7;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d08;SS_NoTargetTable;;8;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d09;SS_SequenceOrTableTooLong;;9;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d0b;SS_IsFallbackSequence;;11;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d0c;SS_AccessDenied;;12;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0d0e;SS_TableInUse;;14;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0da1;SS_TargetTableNotReached;;161;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0da2;SS_TableCheckFailed;;162;SUBSYSTEM;fsfw/src/fsfw/subsystem/Subsystem.h
0x0b01;SB_ChildNotFound;;1;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x0b02;SB_ChildInfoUpdated;;2;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x0b03;SB_ChildDoesntHaveModes;;3;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x0b04;SB_CouldNotInsertChild;;4;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x0b05;SB_TableContainsInvalidObjectId;;5;SUBSYSTEM_BASE;fsfw/src/fsfw/subsystem/SubsystemBase.h
0x3e00;HKM_QueueOrDestinationInvalid;;0;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
0x3e01;HKM_WrongHkPacketType;;1;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
0x3e02;HKM_ReportingStatusUnchanged;;2;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
0x3e03;HKM_PeriodicHelperInvalid;;3;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
0x3e04;HKM_PoolobjectNotFound;;4;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
0x3e05;HKM_DatasetNotFound;;5;HOUSEKEEPING_MANAGER;fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
0x3c00;LPIF_PoolEntryNotFound;;0;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h
0x3c01;LPIF_PoolEntryTypeConflict;;1;LOCAL_POOL_OWNER_IF;fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h
0x3da0;PVA_InvalidReadWriteMode;;160;POOL_VARIABLE_IF;fsfw/src/fsfw/datapool/PoolVariableIF.h 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 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 0x0801;DPS_InvalidParameterDefinition;;1;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h
@ -312,35 +203,20 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x0804;DPS_DataSetUninitialised;;4;DATA_SET_CLASS;fsfw/src/fsfw/datapool/DataSetIF.h 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 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 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 0x1c01;TCD_PacketLost;;1;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1001;TIM_NotEnoughInformationForTargetFormat;;1;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h 0x1c02;TCD_DestinationNotFound;;2;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1002;TIM_LengthMismatch;;2;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h 0x1c03;TCD_ServiceIdAlreadyExists;;3;PACKET_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1003;TIM_InvalidTimeFormat;;3;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h 0x1b00;TCC_NoDestinationFound;;0;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1004;TIM_InvalidDayOfYear;;4;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h 0x1b01;TCC_InvalidCcsdsVersion;;1;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1005;TIM_TimeDoesNotFitFormat;;5;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h 0x1b02;TCC_InvalidApid;;2;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x3701;TSI_BadTimestamp;;1;TIME_STAMPER_IF;fsfw/src/fsfw/timemanager/TimeStampIF.h 0x1b03;TCC_InvalidPacketType;;3;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1d01;ATC_ActivityStarted;;1;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h 0x1b04;TCC_InvalidSecHeaderField;;4;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1d02;ATC_InvalidSubservice;;2;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h 0x1b05;TCC_IncorrectPrimaryHeader;;5;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1d03;ATC_IllegalApplicationData;;3;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h 0x1b07;TCC_IncompletePacket;;7;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1d04;ATC_SendTmFailed;;4;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h 0x1b08;TCC_InvalidPusVersion;;8;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x1d05;ATC_Timeout;;5;ACCEPTS_TELECOMMANDS_IF;fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h 0x1b09;TCC_IncorrectChecksum;;9;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x4c00;SPPA_NoPacketFound;;0;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h 0x1b0a;TCC_IllegalPacketSubtype;;10;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x4c01;SPPA_SplitPacket;;1;SPACE_PACKET_PARSER;fsfw/src/fsfw/tmtcservices/SpacePacketParser.h 0x1b0b;TCC_IncorrectSecondaryHeader;;11;TMTC_DISTRIBUTION;fsfw/src/fsfw/tcdistribution/definitions.h
0x2001;CSB_ExecutionComplete;;1;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x2002;CSB_NoStepMessage;;2;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x2003;CSB_ObjectBusy;;3;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x2004;CSB_Busy;;4;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x2005;CSB_InvalidTc;;5;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x2006;CSB_InvalidObject;;6;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x2007;CSB_InvalidReply;;7;COMMAND_SERVICE_BASE;fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
0x1801;FF_Full;;1;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h
0x1802;FF_Empty;;2;FIFO_CLASS;fsfw/src/fsfw/container/FIFOBase.h
0x1601;FMM_MapFull;;1;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h
0x1602;FMM_KeyDoesNotExist;;2;FIXED_MULTIMAP;fsfw/src/fsfw/container/FixedOrderedMultimap.h
0x2501;EV_ListenerNotFound;;1;EVENT_MANAGER_IF;fsfw/src/fsfw/events/EventManagerIF.h
0x1701;HHI_ObjectNotHealthy;;1;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h
0x1702;HHI_InvalidHealthState;;2;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h
0x1703;HHI_IsExternallyControlled;;3;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h
0x3001;POS_InPowerTransition;;1;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h 0x3001;POS_InPowerTransition;;1;POWER_SWITCHER;fsfw/src/fsfw/power/PowerSwitcher.h
0x3002;POS_SwitchStateMismatch;;2;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 0x0501;PS_SwitchOn;;1;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h
@ -348,23 +224,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 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 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 0x0504;PS_FuseOff;;4;POWER_SWITCH_IF;fsfw/src/fsfw/power/PowerSwitchIF.h
0x4300;FILS_GenericFileError;;0;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x3b00;SPH_ConnBroken;;0;SEMAPHORE_IF;fsfw/src/fsfw/osal/common/TcpTmTcServer.h
0x4301;FILS_GenericDirError;;1;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a01;IEC_NoConfigurationTable;;1;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4302;FILS_FilesystemInactive;;2;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a02;IEC_NoCpuTable;;2;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4303;FILS_GenericRenameError;;3;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a03;IEC_InvalidWorkspaceAddress;;3;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4304;FILS_IsBusy;;4;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a04;IEC_TooLittleWorkspace;;4;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4305;FILS_InvalidParameters;;5;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a05;IEC_WorkspaceAllocation;;5;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x430a;FILS_FileDoesNotExist;;10;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a06;IEC_InterruptStackTooSmall;;6;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x430b;FILS_FileAlreadyExists;;11;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a07;IEC_ThreadExitted;;7;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x430c;FILS_NotAFile;;12;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a08;IEC_InconsistentMpInformation;;8;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x430d;FILS_FileLocked;;13;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a09;IEC_InvalidNode;;9;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x430e;FILS_PermissionDenied;;14;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a0a;IEC_NoMpci;;10;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4315;FILS_DirectoryDoesNotExist;;21;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a0b;IEC_BadPacket;;11;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4316;FILS_DirectoryAlreadyExists;;22;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a0c;IEC_OutOfPackets;;12;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4317;FILS_NotADirectory;;23;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a0d;IEC_OutOfGlobalObjects;;13;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x4318;FILS_DirectoryNotEmpty;;24;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a0e;IEC_OutOfProxies;;14;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x431e;FILS_SequencePacketMissingWrite;;30;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h 0x2a0f;IEC_InvalidGlobalId;;15;INTERNAL_ERROR_CODES;fsfw/src/fsfw/osal/InternalErrorCodes.h
0x431f;FILS_SequencePacketMissingRead;;31;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.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 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 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 0x1a03;TRC_HighestValueOol;;3;TRIPLE_REDUNDACY_CHECK;fsfw/src/fsfw/monitoring/TriplexMonitor.h
@ -383,36 +312,74 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x31e2;LIM_WrongPid;;226;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 0x31e3;LIM_WrongLimitId;;227;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h
0x31ee;LIM_MonitorNotFound;;238;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h 0x31ee;LIM_MonitorNotFound;;238;LIMITS_IF;fsfw/src/fsfw/monitoring/MonitoringIF.h
0x3601;CFDP_InvalidTlvType;;1;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3602;CFDP_InvalidDirectiveField;;2;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3603;CFDP_InvalidPduDatafieldLen;;3;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3604;CFDP_InvalidAckDirectiveFields;;4;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3605;CFDP_MetadataCantParseOptions;;5;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3606;CFDP_NakCantParseOptions;;6;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3607;CFDP_FinishedCantParseFsResponses;;7;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3608;CFDP_FilestoreRequiresSecondFile;;8;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x3609;CFDP_FilestoreResponseCantParseFsMessage;;9;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x360a;CFDP_InvalidPduFormat;;10;CFDP;fsfw/src/fsfw/cfdp/definitions.h
0x4300;FILS_GenericFileError;;0;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4301;FILS_GenericDirError;;1;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4302;FILS_FilesystemInactive;;2;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4303;FILS_GenericRenameError;;3;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4304;FILS_IsBusy;;4;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4305;FILS_InvalidParameters;;5;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x430a;FILS_FileDoesNotExist;;10;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x430b;FILS_FileAlreadyExists;;11;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x430c;FILS_NotAFile;;12;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x430d;FILS_FileLocked;;13;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x430e;FILS_PermissionDenied;;14;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4315;FILS_DirectoryDoesNotExist;;21;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4316;FILS_DirectoryAlreadyExists;;22;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4317;FILS_NotADirectory;;23;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x4318;FILS_DirectoryNotEmpty;;24;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x431e;FILS_SequencePacketMissingWrite;;30;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x431f;FILS_SequencePacketMissingRead;;31;FILE_SYSTEM;fsfw/src/fsfw/filesystem/HasFileSystemIF.h
0x2c01;CCS_BcIsSetVrCommand;;1;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2c02;CCS_BcIsUnlockCommand;;2;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cb0;CCS_BcIllegalCommand;;176;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cb1;CCS_BoardReadingNotFinished;;177;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cf0;CCS_NsPositiveW;;240;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cf1;CCS_NsNegativeW;;241;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cf2;CCS_NsLockout;;242;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cf3;CCS_FarmInLockout;;243;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cf4;CCS_FarmInWait;;244;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce0;CCS_WrongSymbol;;224;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce1;CCS_DoubleStart;;225;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce2;CCS_StartSymbolMissed;;226;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce3;CCS_EndWithoutStart;;227;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce4;CCS_TooLarge;;228;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce5;CCS_TooShort;;229;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce6;CCS_WrongTfVersion;;230;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce7;CCS_WrongSpacecraftId;;231;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce8;CCS_NoValidFrameType;;232;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ce9;CCS_CrcFailed;;233;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cea;CCS_VcNotFound;;234;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ceb;CCS_ForwardingFailed;;235;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cec;CCS_ContentTooLarge;;236;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2ced;CCS_ResidualData;;237;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cee;CCS_DataCorrupted;;238;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cef;CCS_IllegalSegmentationFlag;;239;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cd0;CCS_IllegalFlagCombination;;208;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cd1;CCS_ShorterThanHeader;;209;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cd2;CCS_TooShortBlockedPacket;;210;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x2cd3;CCS_TooShortMapExtraction;;211;CCSDS_HANDLER_IF;fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
0x4201;PUS11_InvalidTypeTimeWindow;;1;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4201;PUS11_InvalidTypeTimeWindow;;1;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4202;PUS11_InvalidTimeWindow;;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4202;PUS11_InvalidTimeWindow;;2;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4203;PUS11_TimeshiftingNotPossible;;3;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4203;PUS11_TimeshiftingNotPossible;;3;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4204;PUS11_InvalidRelativeTime;;4;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4204;PUS11_InvalidRelativeTime;;4;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4205;PUS11_ContainedTcTooSmall;;5;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4205;PUS11_ContainedTcTooSmall;;5;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4206;PUS11_ContainedTcCrcMissmatch;;6;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h 0x4206;PUS11_ContainedTcCrcMissmatch;;6;PUS_SERVICE_11;fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x0601;PP_DoItMyself;;1;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h 0x3401;DC_NoReplyReceived;;1;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
0x0602;PP_PointsToVariable;;2;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h 0x3402;DC_ProtocolError;;2;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
0x0603;PP_PointsToMemory;;3;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h 0x3403;DC_Nullpointer;;3;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
0x0604;PP_ActivityCompleted;;4;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h 0x3404;DC_InvalidCookieType;;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
0x0605;PP_PointsToVectorUint8;;5;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h 0x3405;DC_NotActive;;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
0x0606;PP_PointsToVectorUint16;;6;HAS_MEMORY_IF;fsfw/src/fsfw/memory/HasMemoryIF.h 0x3406;DC_TooMuchData;;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.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 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 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 0x03b1;DHB_IgnoreReplyData;;177;DEVICE_HANDLER_BASE;fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
@ -422,12 +389,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 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 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 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 0x1201;AB_NeedSecondStep;;1;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x3402;DC_ProtocolError;;2;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h 0x1202;AB_NeedToReconfigure;;2;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x3403;DC_Nullpointer;;3;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h 0x1203;AB_ModeFallback;;3;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x3404;DC_InvalidCookieType;;4;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h 0x1204;AB_ChildNotCommandable;;4;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x3405;DC_NotActive;;5;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h 0x1205;AB_NeedToChangeHealth;;5;ASSEMBLY_BASE;fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x3406;DC_TooMuchData;;6;DEVICE_COMMUNICATION_IF;fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.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 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 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 0x27a2;DHI_CommandAlreadySent;;162;DEVICE_HANDLER_IF;fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
@ -449,28 +416,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 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 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 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 0x2401;MT_TooDetailedRequest;;1;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x1402;SE_StreamTooShort;;2;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h 0x2402;MT_TooGeneralRequest;;2;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x1403;SE_TooManyElements;;3;SERIALIZE_IF;fsfw/src/fsfw/serialize/SerializeIF.h 0x2403;MT_NoMatch;;3;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x4500;HSPI_HalTimeoutRetval;;0;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h 0x2404;MT_Full;;4;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x4501;HSPI_HalBusyRetval;;1;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h 0x2405;MT_NewNodeCreated;;5;MATCH_TREE_CLASS;fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
0x4502;HSPI_HalErrorRetval;;2;HAL_SPI;fsfw/src/fsfw_hal/stm32h7/spi/spiDefinitions.h 0x3f01;DLEE_NoPacketFound;;1;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h
0x4601;HURT_UartReadFailure;;1;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h 0x3f02;DLEE_PossiblePacketLoss;;2;DLE_ENCODER;fsfw/src/fsfw/globalfunctions/DleParser.h
0x4602;HURT_UartReadSizeMissmatch;;2;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h 0x2f01;ASC_TooLongForTargetType;;1;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x4603;HURT_UartRxBufferTooSmall;;3;HAL_UART;fsfw/src/fsfw_hal/linux/serial/SerialComIF.h 0x2f02;ASC_InvalidCharacters;;2;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x4801;HGIO_UnknownGpioId;;1;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x2f03;ASC_BufferTooSmall;;3;ASCII_CONVERTER;fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x4802;HGIO_DriveGpioFailure;;2;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x1701;HHI_ObjectNotHealthy;;1;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h
0x4803;HGIO_GpioTypeFailure;;3;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x1702;HHI_InvalidHealthState;;2;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h
0x4804;HGIO_GpioInvalidInstance;;4;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x1703;HHI_IsExternallyControlled;;3;HAS_HEALTH_IF;fsfw/src/fsfw/health/HasHealthIF.h
0x4805;HGIO_GpioDuplicateDetected;;5;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x3201;CF_ObjectHasNoFunctions;;1;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h
0x4806;HGIO_GpioInitFailed;;6;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x3202;CF_AlreadyCommanding;;2;COMMANDS_ACTIONS_IF;fsfw/src/fsfw/action/CommandsActionsIF.h
0x4807;HGIO_GpioGetValueFailed;;7;HAL_GPIO;fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h 0x3301;HF_IsBusy;;1;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h
0x4400;UXOS_ExecutionFinished;Execution of the current command has finished;0;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h 0x3302;HF_InvalidParameters;;2;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.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 0x3303;HF_ExecutionFinished;;3;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h
0x4402;UXOS_BytesRead;Some bytes have been read from the executing process;2;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h 0x3304;HF_InvalidActionId;;4;HAS_ACTIONS_IF;fsfw/src/fsfw/action/HasActionsIF.h
0x4403;UXOS_CommandError;Command execution failed;3;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h 0x1000;TIM_UnsupportedTimeFormat;;0;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h
0x4404;UXOS_NoCommandLoadedOrPending;;4;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.h 0x1001;TIM_NotEnoughInformationForTargetFormat;;1;CCSDS_TIME_HELPER_CLASS;fsfw/src/fsfw/timemanager/CCSDSTime.h
0x4406;UXOS_PcloseCallError;;6;LINUX_OSAL;fsfw/src/fsfw_hal/linux/CommandExecutor.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
0x7000;SCBU_KeyNotFound;;0;SCRATCH_BUFFER;bsp_q7s/memory/scratchApi.h
0x64a0;FSHLP_SdNotMounted;SD card specified with path string not mounted;160;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h 0x64a0;FSHLP_SdNotMounted;SD card specified with path string not mounted;160;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h
0x64a1;FSHLP_FileNotExists;Specified file does not exist on filesystem;161;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h 0x64a1;FSHLP_FileNotExists;Specified file does not exist on filesystem;161;FILE_SYSTEM_HELPER;bsp_q7s/fs/FilesystemHelper.h
0x6f00;SDMA_OpOngoing;;0;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h 0x6f00;SDMA_OpOngoing;;0;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h
@ -483,7 +480,9 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x6f0d;SDMA_UnmountError;;13;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h 0x6f0d;SDMA_UnmountError;;13;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h
0x6f0e;SDMA_SystemCallError;;14;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h 0x6f0e;SDMA_SystemCallError;;14;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h
0x6f0f;SDMA_PopenCallError;;15;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h 0x6f0f;SDMA_PopenCallError;;15;SD_CARD_MANAGER;bsp_q7s/fs/SdCardManager.h
0x7000;SCBU_KeyNotFound;;0;SCRATCH_BUFFER;bsp_q7s/memory/scratchApi.h 0x65a0;PLMPHLP_FileClosedAccidentally;File accidentally close;160;PLOC_MPSOC_HELPER;linux/devices/ploc/PlocMPSoCHelper.h
0x5ea0;PLMEMDUMP_MramAddressTooHigh;The capacity of the MRAM amounts to 512 kB. Thus the maximum address must not be higher than 0x7d000.;160;PLOC_MEMORY_DUMPER;linux/devices/ploc/PlocMemoryDumper.h
0x5ea1;PLMEMDUMP_MramInvalidAddressCombination;The specified end address is lower than the start address;161;PLOC_MEMORY_DUMPER;linux/devices/ploc/PlocMemoryDumper.h
0x57a0;PLSPVhLP_FileClosedAccidentally;File accidentally close;160;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h 0x57a0;PLSPVhLP_FileClosedAccidentally;File accidentally close;160;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h
0x57a1;PLSPVhLP_ProcessTerminated;Process has been terminated by command;161;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h 0x57a1;PLSPVhLP_ProcessTerminated;Process has been terminated by command;161;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h
0x57a2;PLSPVhLP_PathNotExists;Received command with invalid pathname;162;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h 0x57a2;PLSPVhLP_PathNotExists;Received command with invalid pathname;162;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h
@ -494,46 +493,16 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x5703;PLSPVhLP_PossiblePacketLossConsecutiveStart;;3;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h 0x5703;PLSPVhLP_PossiblePacketLossConsecutiveStart;;3;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h
0x5704;PLSPVhLP_PossiblePacketLossConsecutiveEnd;;4;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h 0x5704;PLSPVhLP_PossiblePacketLossConsecutiveEnd;;4;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h
0x5705;PLSPVhLP_HdlcError;;5;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h 0x5705;PLSPVhLP_HdlcError;;5;PLOC_SUPV_HELPER;linux/devices/ploc/PlocSupvUartMan.h
0x65a0;PLMPHLP_FileClosedAccidentally;File accidentally close;160;PLOC_MPSOC_HELPER;linux/devices/ploc/PlocMPSoCHelper.h 0x67a0;MPSOCRTVIF_CrcFailure;Space Packet received from PLOC has invalid CRC;160;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x5ea0;PLMEMDUMP_MramAddressTooHigh;The capacity of the MRAM amounts to 512 kB. Thus the maximum address must not be higher than 0x7d000.;160;PLOC_MEMORY_DUMPER;linux/devices/ploc/PlocMemoryDumper.h 0x67a1;MPSOCRTVIF_ReceivedAckFailure;Received ACK failure reply from PLOC;161;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x5ea1;PLMEMDUMP_MramInvalidAddressCombination;The specified end address is lower than the start address;161;PLOC_MEMORY_DUMPER;linux/devices/ploc/PlocMemoryDumper.h 0x67a2;MPSOCRTVIF_ReceivedExeFailure;Received execution failure reply from PLOC;162;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x53a0;STRH_TemperatureReqFailed;Status in temperature reply signals error;160;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h 0x67a3;MPSOCRTVIF_InvalidApid;Received space packet with invalid APID from PLOC;163;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x53a1;STRH_PingFailed;Ping command failed;161;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h 0x67a4;MPSOCRTVIF_InvalidLength;Received command with invalid length;164;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x53a2;STRH_VersionReqFailed;Status in version reply signals error;162;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h 0x67a5;MPSOCRTVIF_FilenameTooLong;Filename of file in OBC filesystem is too long;165;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x6201;JSONBASE_JsonFileNotExists;Specified json file does not exist;1;ARCSEC_JSON_BASE;linux/devices/startracker/ArcsecJsonParamBase.h 0x67a6;MPSOCRTVIF_MpsocHelperExecuting;MPSoC helper is currently executing a command;166;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x6202;JSONBASE_SetNotExists;Requested set does not exist in json file;2;ARCSEC_JSON_BASE;linux/devices/startracker/ArcsecJsonParamBase.h 0x67a7;MPSOCRTVIF_MpsocFilenameTooLong;Filename of MPSoC file is to long (max. 256 bytes);167;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x6203;JSONBASE_ParamNotExists;Requested parameter does not exist in json file;3;ARCSEC_JSON_BASE;linux/devices/startracker/ArcsecJsonParamBase.h 0x67a8;MPSOCRTVIF_InvalidParameter;Command has invalid parameter;168;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x53a3;STRH_InterfaceReqFailed;Status in interface reply signals error;163;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h 0x67a9;MPSOCRTVIF_NameTooLong;Received command has file string with invalid length;169;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x53a4;STRH_PowerReqFailed;Status in power reply signals error;164;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53a5;STRH_SetParamFailed;Status of reply to parameter set command signals error;165;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53a6;STRH_ActionFailed;Status of reply to action command signals error;166;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53a7;STRH_FilePathTooLong;Received invalid path string. Exceeds allowed length;167;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53a8;STRH_FilenameTooLong;Name of file received with command is too long;168;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53a9;STRH_InvalidProgram;Received version reply with invalid program ID;169;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53aa;STRH_ReplyError;Status field reply signals error;170;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53ab;STRH_CommandTooShort;Received command which is too short (some data is missing for proper execution);171;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53ac;STRH_InvalidLength;Received command with invalid length (too few or too many parameters);172;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53ad;STRH_RegionMismatch;Region mismatch between send and received data;173;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53ae;STRH_AddressMismatch;Address mismatch between send and received data;174;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53af;STRH_LengthMismatch;Length field mismatch between send and received data;175;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b0;STRH_FileNotExists;Specified file does not exist;176;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b1;STRH_InvalidType;Download blob pixel command has invalid type field;177;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b2;STRH_InvalidId;Received FPGA action command with invalid ID;178;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b3;STRH_ReplyTooShort;Received reply is too short;179;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b4;STRH_CrcFailure;Received reply with invalid CRC;180;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b5;STRH_StrHelperExecuting;Star tracker handler currently executing a command and using the communication interface;181;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b6;STRH_StartrackerAlreadyBooted;Star tracker is already in firmware mode;182;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b7;STRH_StartrackerRunningFirmware;Star tracker is in firmware mode but must be in bootloader mode to execute this command;183;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b8;STRH_StartrackerRunningBootloader;Star tracker is in bootloader mode but must be in firmware mode to execute this command;184;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x5ca0;STRHLP_SdNotMounted;SD card specified in path string not mounted;160;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca1;STRHLP_FileNotExists;Specified file does not exist on filesystem;161;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca2;STRHLP_PathNotExists;Specified path does not exist;162;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca3;STRHLP_FileCreationFailed;Failed to create download image or read flash file;163;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca4;STRHLP_RegionMismatch;Region in flash write/read reply does not match expected region;164;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca5;STRHLP_AddressMismatch;Address in flash write/read reply does not match expected address;165;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca6;STRHLP_LengthMismatch;Length in flash write/read reply does not match expected length;166;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca7;STRHLP_StatusError;Status field in reply signals error;167;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca8;STRHLP_InvalidTypeId;Reply has invalid type ID (should be of action reply type);168;STR_HELPER;linux/devices/startracker/StrHelper.h
0x68a0;SPVRTVIF_CrcFailure;Space Packet received from PLOC supervisor has invalid CRC;160;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h 0x68a0;SPVRTVIF_CrcFailure;Space Packet received from PLOC supervisor has invalid CRC;160;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
0x68a1;SPVRTVIF_InvalidServiceId;;161;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h 0x68a1;SPVRTVIF_InvalidServiceId;;161;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
0x68a2;SPVRTVIF_ReceivedAckFailure;Received ACK failure reply from PLOC supervisor;162;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h 0x68a2;SPVRTVIF_ReceivedAckFailure;Received ACK failure reply from PLOC supervisor;162;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
@ -558,20 +527,46 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x68b5;SPVRTVIF_SupvHelperExecuting;Supervisor helper task ist currently executing a command (wait until helper tas has finished or interrupt by sending the terminate command);181;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h 0x68b5;SPVRTVIF_SupvHelperExecuting;Supervisor helper task ist currently executing a command (wait until helper tas has finished or interrupt by sending the terminate command);181;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
0x68c0;SPVRTVIF_BufTooSmall;;192;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h 0x68c0;SPVRTVIF_BufTooSmall;;192;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
0x68c1;SPVRTVIF_NoReplyTimeout;;193;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h 0x68c1;SPVRTVIF_NoReplyTimeout;;193;SUPV_RETURN_VALUES_IF;linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
0x67a0;MPSOCRTVIF_CrcFailure;Space Packet received from PLOC has invalid CRC;160;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x67a1;MPSOCRTVIF_ReceivedAckFailure;Received ACK failure reply from PLOC;161;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x67a2;MPSOCRTVIF_ReceivedExeFailure;Received execution failure reply from PLOC;162;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x67a3;MPSOCRTVIF_InvalidApid;Received space packet with invalid APID from PLOC;163;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x67a4;MPSOCRTVIF_InvalidLength;Received command with invalid length;164;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x67a5;MPSOCRTVIF_FilenameTooLong;Filename of file in OBC filesystem is too long;165;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x67a6;MPSOCRTVIF_MpsocHelperExecuting;MPSoC helper is currently executing a command;166;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x67a7;MPSOCRTVIF_MpsocFilenameTooLong;Filename of MPSoC file is to long (max. 256 bytes);167;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x67a8;MPSOCRTVIF_InvalidParameter;Command has invalid parameter;168;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x67a9;MPSOCRTVIF_NameTooLong;Received command has file string with invalid length;169;MPSOC_RETURN_VALUES_IF;linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x54e0;DWLPWRON_InvalidMode;Received command has invalid JESD mode (valid modes are 0 - 5);224;DWLPWRON_CMD;linux/devices/devicedefinitions/PlocMPSoCDefinitions.h 0x54e0;DWLPWRON_InvalidMode;Received command has invalid JESD mode (valid modes are 0 - 5);224;DWLPWRON_CMD;linux/devices/devicedefinitions/PlocMPSoCDefinitions.h
0x54e1;DWLPWRON_InvalidLaneRate;Received command has invalid lane rate (valid lane rate are 0 - 9);225;DWLPWRON_CMD;linux/devices/devicedefinitions/PlocMPSoCDefinitions.h 0x54e1;DWLPWRON_InvalidLaneRate;Received command has invalid lane rate (valid lane rate are 0 - 9);225;DWLPWRON_CMD;linux/devices/devicedefinitions/PlocMPSoCDefinitions.h
0x5402;DWLPWRON_InvalidCrc;;2;DWLPWRON_CMD;linux/devices/ScexHelper.h 0x6201;JSONBASE_JsonFileNotExists;Specified json file does not exist;1;ARCSEC_JSON_BASE;linux/devices/startracker/ArcsecJsonParamBase.h
0x59a0;IPCI_PapbBusy;;160;CCSDS_IP_CORE_BRIDGE;linux/ipcore/PapbVcInterface.h 0x6202;JSONBASE_SetNotExists;Requested set does not exist in json file;2;ARCSEC_JSON_BASE;linux/devices/startracker/ArcsecJsonParamBase.h
0x6203;JSONBASE_ParamNotExists;Requested parameter does not exist in json file;3;ARCSEC_JSON_BASE;linux/devices/startracker/ArcsecJsonParamBase.h
0x53a0;STRH_TemperatureReqFailed;Status in temperature reply signals error;160;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53a1;STRH_PingFailed;Ping command failed;161;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53a2;STRH_VersionReqFailed;Status in version reply signals error;162;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x5ca0;STRHLP_SdNotMounted;SD card specified in path string not mounted;160;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca1;STRHLP_FileNotExists;Specified file does not exist on filesystem;161;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca2;STRHLP_PathNotExists;Specified path does not exist;162;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca3;STRHLP_FileCreationFailed;Failed to create download image or read flash file;163;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca4;STRHLP_RegionMismatch;Region in flash write/read reply does not match expected region;164;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca5;STRHLP_AddressMismatch;Address in flash write/read reply does not match expected address;165;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca6;STRHLP_LengthMismatch;Length in flash write/read reply does not match expected length;166;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca7;STRHLP_StatusError;Status field in reply signals error;167;STR_HELPER;linux/devices/startracker/StrHelper.h
0x5ca8;STRHLP_InvalidTypeId;Reply has invalid type ID (should be of action reply type);168;STR_HELPER;linux/devices/startracker/StrHelper.h
0x53a3;STRH_InterfaceReqFailed;Status in interface reply signals error;163;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53a4;STRH_PowerReqFailed;Status in power reply signals error;164;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53a5;STRH_SetParamFailed;Status of reply to parameter set command signals error;165;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53a6;STRH_ActionFailed;Status of reply to action command signals error;166;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53a7;STRH_FilePathTooLong;Received invalid path string. Exceeds allowed length;167;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53a8;STRH_FilenameTooLong;Name of file received with command is too long;168;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53a9;STRH_InvalidProgram;Received version reply with invalid program ID;169;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53aa;STRH_ReplyError;Status field reply signals error;170;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53ab;STRH_CommandTooShort;Received command which is too short (some data is missing for proper execution);171;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53ac;STRH_InvalidLength;Received command with invalid length (too few or too many parameters);172;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53ad;STRH_RegionMismatch;Region mismatch between send and received data;173;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53ae;STRH_AddressMismatch;Address mismatch between send and received data;174;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53af;STRH_LengthMismatch;Length field mismatch between send and received data;175;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b0;STRH_FileNotExists;Specified file does not exist;176;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b1;STRH_InvalidType;Download blob pixel command has invalid type field;177;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b2;STRH_InvalidId;Received FPGA action command with invalid ID;178;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b3;STRH_ReplyTooShort;Received reply is too short;179;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b4;STRH_CrcFailure;Received reply with invalid CRC;180;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b5;STRH_StrHelperExecuting;Star tracker handler currently executing a command and using the communication interface;181;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b6;STRH_StartrackerAlreadyBooted;Star tracker is already in firmware mode;182;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b7;STRH_StartrackerRunningFirmware;Star tracker is in firmware mode but must be in bootloader mode to execute this command;183;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x53b8;STRH_StartrackerRunningBootloader;Star tracker is in bootloader mode but must be in firmware mode to execute this command;184;STR_HANDLER;linux/devices/startracker/StarTrackerHandler.h
0x5302;STRH_InvalidCrc;;2;STR_HANDLER;linux/devices/ScexHelper.h
0x5aa0;PTME_UnknownVcId;;160;PTME;linux/ipcore/Ptme.h 0x5aa0;PTME_UnknownVcId;;160;PTME;linux/ipcore/Ptme.h
0x5fa0;PDEC_AbandonedCltu;;160;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fa0;PDEC_AbandonedCltu;;160;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fa1;PDEC_FrameDirty;;161;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fa1;PDEC_FrameDirty;;161;PDEC_HANDLER;linux/ipcore/PdecHandler.h
@ -592,3 +587,4 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x61a1;RS_BadBitRate;Bad bitrate has been commanded (e.g. 0);161;RATE_SETTER;linux/ipcore/PtmeConfig.h 0x61a1;RS_BadBitRate;Bad bitrate has been commanded (e.g. 0);161;RATE_SETTER;linux/ipcore/PtmeConfig.h
0x61a2;RS_ClkInversionFailed;Failed to invert clock and thus change the time the data is updated with respect to the tx clock;162;RATE_SETTER;linux/ipcore/PtmeConfig.h 0x61a2;RS_ClkInversionFailed;Failed to invert clock and thus change the time the data is updated with respect to the tx clock;162;RATE_SETTER;linux/ipcore/PtmeConfig.h
0x61a3;RS_TxManipulatorConfigFailed;Failed to change configuration bit of tx clock manipulator;163;RATE_SETTER;linux/ipcore/PtmeConfig.h 0x61a3;RS_TxManipulatorConfigFailed;Failed to change configuration bit of tx clock manipulator;163;RATE_SETTER;linux/ipcore/PtmeConfig.h
0x59a0;IPCI_PapbBusy;;160;CCSDS_IP_CORE_BRIDGE;linux/ipcore/PapbVcInterface.h

1 Full ID (hex) Name Description Unique ID Subsytem Name File Path
2 0x0000 OK System-wide code for ok. 0 HasReturnvaluesIF fsfw/returnvalues/returnvalue.h
3 0x0001 Failed Unspecified system-wide code for failed. 1 HasReturnvaluesIF fsfw/returnvalues/returnvalue.h
4 0x60a0 0x63a0 CCSDS_CommandNotImplemented NVMB_KeyNotExists Received action message with unknown action id Specified key does not exist in json file 160 CCSDS_HANDLER NVM_PARAM_BASE mission/tmtc/CcsdsIpCoreHandler.h mission/memory/NVMParameterBase.h
5 0x63a0 0x6300 NVMB_KeyNotExists NVMB_Busy Specified key does not exist in json file 160 0 NVM_PARAM_BASE mission/memory/NVMParameterBase.h mission/system/objects/Stack5VHandler.h
6 0x6d01 0x52b0 ACSDTB_DetumbleNoSensordata RWHA_SpiWriteFailure No description 1 176 ACS_DETUMBLE RW_HANDLER mission/controller/acs/control/Detumble.h mission/devices/devicedefinitions/rwHelpers.h
7 0x6c01 0x52b1 ACSPTG_PtgctrlMekfInputInvalid RWHA_SpiReadFailure No description Used by the spi send function to tell a failing read call 1 177 ACS_PTG RW_HANDLER mission/controller/acs/control/PtgCtrl.h mission/devices/devicedefinitions/rwHelpers.h
8 0x6b01 0x52b2 ACSSAF_SafectrlMekfInputInvalid RWHA_MissingStartSign No description Can be used by the HDLC decoding mechanism to inform about a missing start sign 0x7E 1 178 ACS_SAFE RW_HANDLER mission/controller/acs/control/SafeCtrl.h mission/devices/devicedefinitions/rwHelpers.h
9 0x6a02 0x52b3 ACSMEKF_MekfUninitialized RWHA_InvalidSubstitute No description Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination 2 179 ACS_MEKF RW_HANDLER mission/controller/acs/MultiplicativeKalmanFilter.h mission/devices/devicedefinitions/rwHelpers.h
10 0x6a03 0x52b4 ACSMEKF_MekfNoGyrData RWHA_MissingEndSign No description HDLC decoding mechanism never receives the end sign 0x7E 3 180 ACS_MEKF RW_HANDLER mission/controller/acs/MultiplicativeKalmanFilter.h mission/devices/devicedefinitions/rwHelpers.h
11 0x6a04 0x52b5 ACSMEKF_MekfNoModelVectors RWHA_NoReply No description Reaction wheel only responds with empty frames. 4 181 ACS_MEKF RW_HANDLER mission/controller/acs/MultiplicativeKalmanFilter.h mission/devices/devicedefinitions/rwHelpers.h
12 0x6a05 0x52b6 ACSMEKF_MekfNoSusMgmStrData RWHA_NoStartMarker No description Expected a start marker as first byte 5 182 ACS_MEKF RW_HANDLER mission/controller/acs/MultiplicativeKalmanFilter.h mission/devices/devicedefinitions/rwHelpers.h
13 0x6a06 0x52b7 ACSMEKF_MekfCovarianceInversionFailed RWHA_SpiReadTimeout No description Timeout when reading reply 6 183 ACS_MEKF RW_HANDLER mission/controller/acs/MultiplicativeKalmanFilter.h mission/devices/devicedefinitions/rwHelpers.h
0x6a07 ACSMEKF_MekfInitialized No description 7 ACS_MEKF mission/controller/acs/MultiplicativeKalmanFilter.h
0x6a08 ACSMEKF_MekfRunning No description 8 ACS_MEKF mission/controller/acs/MultiplicativeKalmanFilter.h
0x6900 ACSCTRL_FileDeletionFailed No description 0 ACS_CTRL mission/controller/AcsController.h
0x52b0 RWHA_SpiWriteFailure No description 176 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
0x52b1 RWHA_SpiReadFailure Used by the spi send function to tell a failing read call 177 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.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/devicedefinitions/rwHelpers.h
0x52b3 RWHA_InvalidSubstitute Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination 179 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
0x52b4 RWHA_MissingEndSign HDLC decoding mechanism never receives the end sign 0x7E 180 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
0x52b5 RWHA_NoReply Reaction wheel only responds with empty frames. 181 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
0x52b6 RWHA_NoStartMarker Expected a start marker as first byte 182 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
0x52b7 RWHA_SpiReadTimeout Timeout when reading reply 183 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
0x5100 IMTQ_InvalidCommandCode No description 0 IMTQ_HANDLER mission/devices/devicedefinitions/imtqHelpers.h
0x5101 IMTQ_MgmMeasurementLowLevelError No description 1 IMTQ_HANDLER mission/devices/devicedefinitions/imtqHelpers.h
0x5102 IMTQ_ActuateCmdLowLevelError No description 2 IMTQ_HANDLER mission/devices/devicedefinitions/imtqHelpers.h
14 0x5103 0x58a0 IMTQ_ParameterMissing SUSS_ErrorUnlockMutex No description 3 160 IMTQ_HANDLER SUS_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SusHandler.h
15 0x5104 0x58a1 IMTQ_ParameterInvalid SUSS_ErrorLockMutex No description 4 161 IMTQ_HANDLER SUS_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SusHandler.h
16 0x5105 0x66a0 IMTQ_CcUnavailable SADPL_CommandNotSupported No description 5 160 IMTQ_HANDLER SA_DEPL_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SolarArrayDeploymentHandler.h
17 0x5106 0x66a1 IMTQ_InternalProcessingError SADPL_DeploymentAlreadyExecuting No description 6 161 IMTQ_HANDLER SA_DEPL_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SolarArrayDeploymentHandler.h
18 0x5107 0x66a2 IMTQ_RejectedWithoutReason SADPL_MainSwitchTimeoutFailure No description 7 162 IMTQ_HANDLER SA_DEPL_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SolarArrayDeploymentHandler.h
19 0x5108 0x66a3 IMTQ_CmdErrUnknown SADPL_SwitchingDeplSa1Failed No description 8 163 IMTQ_HANDLER SA_DEPL_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SolarArrayDeploymentHandler.h
20 0x51a7 0x66a4 IMTQ_UnexpectedSelfTestReply SADPL_SwitchingDeplSa2Failed The status reply to a self test command was received but no self test command has been sent. This should normally never happen. 167 164 IMTQ_HANDLER SA_DEPL_HANDLER mission/devices/devicedefinitions/imtqHelpers.h mission/devices/SolarArrayDeploymentHandler.h
21 0x66a0 0x51a0 SADPL_CommandNotSupported IMTQ_InvalidSpeed No description Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000] 160 SA_DEPL_HANDLER IMTQ_HANDLER mission/devices/SolarArrayDeploymentHandler.h mission/devices/RwHandler.h
22 0x51a1 IMTQ_InvalidRampTime Action Message with invalid ramp time was received. 161 IMTQ_HANDLER mission/devices/RwHandler.h
23 0x51a2 IMTQ_SetSpeedCommandInvalidLength Received set speed command has invalid length. Should be 6. 162 IMTQ_HANDLER mission/devices/RwHandler.h
24 0x51a3 IMTQ_ExecutionFailed Command execution failed 163 IMTQ_HANDLER mission/devices/RwHandler.h
25 0x51a4 IMTQ_CrcError Reaction wheel reply has invalid crc 164 IMTQ_HANDLER mission/devices/RwHandler.h
26 0x51a5 IMTQ_ValueNotRead 165 IMTQ_HANDLER mission/devices/RwHandler.h
27 0x66a1 0x51a6 SADPL_DeploymentAlreadyExecuting IMTQ_CmdErrUnknown No description 161 166 SA_DEPL_HANDLER IMTQ_HANDLER mission/devices/SolarArrayDeploymentHandler.h mission/devices/ImtqHandler.h
28 0x66a2 0x51a7 SADPL_MainSwitchTimeoutFailure IMTQ_UnexpectedSelfTestReply No description The status reply to a self test command was received but no self test command has been sent. This should normally never happen. 162 167 SA_DEPL_HANDLER IMTQ_HANDLER mission/devices/SolarArrayDeploymentHandler.h mission/devices/ImtqHandler.h
29 0x66a3 0x50a0 SADPL_SwitchingDeplSa1Failed SYRLINKS_CrcFailure No description 163 160 SA_DEPL_HANDLER SYRLINKS_HANDLER mission/devices/SolarArrayDeploymentHandler.h mission/devices/SyrlinksHandler.h
35 0x50a4 0x50a6 SYRLINKS_BadEndOfFrameAck SYRLINKS_BadCrcAck No description 164 166 SYRLINKS_HANDLER mission/devices/SyrlinksHandler.h
36 0x50a5 0x50a7 SYRLINKS_UnknownCommandIdAck SYRLINKS_ReplyWrongSize No description 165 167 SYRLINKS_HANDLER mission/devices/SyrlinksHandler.h
37 0x50a6 0x50a8 SYRLINKS_BadCrcAck SYRLINKS_MissingStartFrameCharacter No description 166 168 SYRLINKS_HANDLER mission/devices/SyrlinksHandler.h
38 0x50a7 0x5d00 SYRLINKS_ReplyWrongSize GOMS_PacketTooLong No description 167 0 SYRLINKS_HANDLER GOM_SPACE_HANDLER mission/devices/SyrlinksHandler.h mission/devices/GomspaceDeviceHandler.h
39 0x50a8 0x5d01 SYRLINKS_MissingStartFrameCharacter GOMS_InvalidTableId No description 168 1 SYRLINKS_HANDLER GOM_SPACE_HANDLER mission/devices/SyrlinksHandler.h mission/devices/GomspaceDeviceHandler.h
40 0x58a0 0x5d02 SUSS_ErrorUnlockMutex GOMS_InvalidAddress No description 160 2 SUS_HANDLER GOM_SPACE_HANDLER mission/devices/SusHandler.h mission/devices/GomspaceDeviceHandler.h
41 0x58a1 0x5d03 SUSS_ErrorLockMutex GOMS_InvalidParamSize No description 161 3 SUS_HANDLER GOM_SPACE_HANDLER mission/devices/SusHandler.h mission/devices/GomspaceDeviceHandler.h
42 0x4fa1 0x5d04 HEATER_InvalidRampTime GOMS_InvalidPayloadSize Action Message with invalid ramp time was received. 161 4 HEATER_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h mission/devices/GomspaceDeviceHandler.h
43 0x4fa2 0x5d05 HEATER_SetSpeedCommandInvalidLength GOMS_UnknownReplyId Received set speed command has invalid length. Should be 6. 162 5 HEATER_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h mission/devices/GomspaceDeviceHandler.h
44 0x4fa3 0x4fa1 HEATER_ExecutionFailed HEATER_CommandNotSupported Command execution failed 163 161 HEATER_HANDLER mission/devices/RwHandler.h mission/devices/HeaterHandler.h
45 0x4fa2 HEATER_InitFailed 162 HEATER_HANDLER mission/devices/HeaterHandler.h
46 0x4fa3 HEATER_InvalidSwitchNr 163 HEATER_HANDLER mission/devices/HeaterHandler.h
47 0x4fa4 HEATER_MainSwitchSetTimeout 164 HEATER_HANDLER mission/devices/HeaterHandler.h
48 0x4fa5 HEATER_CommandAlreadyWaiting 165 HEATER_HANDLER mission/devices/HeaterHandler.h
49 0x60a0 CCSDS_CommandNotImplemented Received action message with unknown action id 160 CCSDS_HANDLER mission/tmtc/CcsdsIpCoreHandler.h
50 0x4fa4 0x6a01 HEATER_CrcError ACSSAF_SafectrlMekfInputInvalid Reaction wheel reply has invalid crc 164 1 HEATER_HANDLER ACS_SAFE mission/devices/RwHandler.h mission/controller/acs/control/SafeCtrl.h
51 0x6b01 ACSPTG_PtgctrlMekfInputInvalid 1 ACS_PTG mission/controller/acs/control/PtgCtrl.h
52 0x4fa5 0x6c01 HEATER_ValueNotRead ACSDTB_DetumbleNoSensordata No description 165 1 HEATER_HANDLER ACS_DETUMBLE mission/devices/RwHandler.h mission/controller/acs/control/Detumble.h
53 0x4fa0 0x6901 HEATER_InvalidSpeed ACSKAL_KalmanNoGyrMeas Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000] 160 1 HEATER_HANDLER ACS_KALMAN mission/devices/RwHandler.h mission/controller/acs/MultiplicativeKalmanFilter.h
54 0x5d00 0x6902 GOMS_PacketTooLong ACSKAL_KalmanNoModel No description 0 2 GOM_SPACE_HANDLER ACS_KALMAN mission/devices/GomspaceDeviceHandler.h mission/controller/acs/MultiplicativeKalmanFilter.h
55 0x5d01 0x6903 GOMS_InvalidTableId ACSKAL_KalmanInversionFailed No description 1 3 GOM_SPACE_HANDLER ACS_KALMAN mission/devices/GomspaceDeviceHandler.h mission/controller/acs/MultiplicativeKalmanFilter.h
56 0x5d02 0x4500 GOMS_InvalidAddress HSPI_OpeningFileFailed No description 2 0 GOM_SPACE_HANDLER HAL_SPI mission/devices/GomspaceDeviceHandler.h fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
57 0x5d03 0x4501 GOMS_InvalidParamSize HSPI_FullDuplexTransferFailed No description 3 1 GOM_SPACE_HANDLER HAL_SPI mission/devices/GomspaceDeviceHandler.h fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
58 0x5d04 0x4502 GOMS_InvalidPayloadSize HSPI_HalfDuplexTransferFailed No description 4 2 GOM_SPACE_HANDLER HAL_SPI mission/devices/GomspaceDeviceHandler.h fsfw/src/fsfw_hal/linux/spi/SpiComIF.h
59 0x5d05 0x4801 GOMS_UnknownReplyId HGIO_UnknownGpioId No description 5 1 GOM_SPACE_HANDLER HAL_GPIO mission/devices/GomspaceDeviceHandler.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
60 0x38a1 0x4802 SGP4_InvalidEccentricity HGIO_DriveGpioFailure No description 161 2 SGP4PROPAGATOR_CLASS HAL_GPIO fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
61 0x38a2 0x4803 SGP4_InvalidMeanMotion HGIO_GpioTypeFailure No description 162 3 SGP4PROPAGATOR_CLASS HAL_GPIO fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
62 0x38a3 0x4804 SGP4_InvalidPerturbationElements HGIO_GpioInvalidInstance No description 163 4 SGP4PROPAGATOR_CLASS HAL_GPIO fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
63 0x38a4 0x4805 SGP4_InvalidSemiLatusRectum HGIO_GpioDuplicateDetected No description 164 5 SGP4PROPAGATOR_CLASS HAL_GPIO fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
64 0x38a5 0x4806 SGP4_InvalidEpochElements HGIO_GpioInitFailed No description 165 6 SGP4PROPAGATOR_CLASS HAL_GPIO fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
65 0x38a6 0x4807 SGP4_SatelliteHasDecayed HGIO_GpioGetValueFailed No description 166 7 SGP4PROPAGATOR_CLASS HAL_GPIO fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h
66 0x38b1 0x4601 SGP4_TleTooOld HURT_UartReadFailure No description 177 1 SGP4PROPAGATOR_CLASS HAL_UART fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
67 0x38b2 0x4602 SGP4_TleNotInitialized HURT_UartReadSizeMissmatch No description 178 2 SGP4PROPAGATOR_CLASS HAL_UART fsfw/src/fsfw/coordinates/Sgp4Propagator.h fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
68 0x2801 0x4603 SM_DataTooLarge HURT_UartRxBufferTooSmall No description 1 3 STORAGE_MANAGER_IF HAL_UART fsfw/src/fsfw/storagemanager/StorageManagerIF.h fsfw/src/fsfw_hal/linux/serial/SerialComIF.h
69 0x2802 0x4400 SM_DataStorageFull UXOS_ExecutionFinished No description Execution of the current command has finished 2 0 STORAGE_MANAGER_IF LINUX_OSAL fsfw/src/fsfw/storagemanager/StorageManagerIF.h fsfw/src/fsfw_hal/linux/CommandExecutor.h
70 0x2803 0x4401 SM_IllegalStorageId UXOS_CommandPending No description Command is pending. This will also be returned if the user tries to load another command but a command is still pending 3 1 STORAGE_MANAGER_IF LINUX_OSAL fsfw/src/fsfw/storagemanager/StorageManagerIF.h fsfw/src/fsfw_hal/linux/CommandExecutor.h
71 0x2804 0x4402 SM_DataDoesNotExist UXOS_BytesRead No description Some bytes have been read from the executing process 4 2 STORAGE_MANAGER_IF LINUX_OSAL fsfw/src/fsfw/storagemanager/StorageManagerIF.h fsfw/src/fsfw_hal/linux/CommandExecutor.h
72 0x2805 0x4403 SM_IllegalAddress UXOS_CommandError No description Command execution failed 5 3 STORAGE_MANAGER_IF LINUX_OSAL fsfw/src/fsfw/storagemanager/StorageManagerIF.h fsfw/src/fsfw_hal/linux/CommandExecutor.h
73 0x2806 0x4404 SM_PoolTooLarge UXOS_NoCommandLoadedOrPending No description 6 4 STORAGE_MANAGER_IF LINUX_OSAL fsfw/src/fsfw/storagemanager/StorageManagerIF.h fsfw/src/fsfw_hal/linux/CommandExecutor.h
74 0x1a01 0x4406 TRC_NotEnoughSensors UXOS_PcloseCallError No description 1 6 TRIPLE_REDUNDACY_CHECK LINUX_OSAL fsfw/src/fsfw/monitoring/TriplexMonitor.h fsfw/src/fsfw_hal/linux/CommandExecutor.h
75 0x1a02 0x2801 TRC_LowestValueOol SM_DataTooLarge No description 2 1 TRIPLE_REDUNDACY_CHECK STORAGE_MANAGER_IF fsfw/src/fsfw/monitoring/TriplexMonitor.h fsfw/src/fsfw/storagemanager/StorageManagerIF.h
76 0x1a03 0x2802 TRC_HighestValueOol SM_DataStorageFull No description 3 2 TRIPLE_REDUNDACY_CHECK STORAGE_MANAGER_IF fsfw/src/fsfw/monitoring/TriplexMonitor.h fsfw/src/fsfw/storagemanager/StorageManagerIF.h
77 0x1a04 0x2803 TRC_BothValuesOol SM_IllegalStorageId No description 4 3 TRIPLE_REDUNDACY_CHECK STORAGE_MANAGER_IF fsfw/src/fsfw/monitoring/TriplexMonitor.h fsfw/src/fsfw/storagemanager/StorageManagerIF.h
78 0x1a05 0x2804 TRC_DuplexOol SM_DataDoesNotExist No description 5 4 TRIPLE_REDUNDACY_CHECK STORAGE_MANAGER_IF fsfw/src/fsfw/monitoring/TriplexMonitor.h fsfw/src/fsfw/storagemanager/StorageManagerIF.h
79 0x3101 0x2805 LIM_Unchecked SM_IllegalAddress No description 1 5 LIMITS_IF STORAGE_MANAGER_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/storagemanager/StorageManagerIF.h
80 0x3102 0x2806 LIM_Invalid SM_PoolTooLarge No description 2 6 LIMITS_IF STORAGE_MANAGER_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/storagemanager/StorageManagerIF.h
81 0x3103 0x0601 LIM_Unselected PP_DoItMyself No description 3 1 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
82 0x3104 0x0602 LIM_BelowLowLimit PP_PointsToVariable No description 4 2 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
83 0x3105 0x0603 LIM_AboveHighLimit PP_PointsToMemory No description 5 3 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
84 0x3106 0x0604 LIM_UnexpectedValue PP_ActivityCompleted No description 6 4 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
85 0x3107 0x0605 LIM_OutOfRange PP_PointsToVectorUint8 No description 7 5 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
86 0x31a0 0x0606 LIM_FirstSample PP_PointsToVectorUint16 No description 160 6 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
87 0x31e0 0x0607 LIM_InvalidSize PP_PointsToVectorUint32 No description 224 7 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
88 0x31e1 0x0608 LIM_WrongType PP_PointsToVectorFloat No description 225 8 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
89 0x31e2 0x06a0 LIM_WrongPid PP_DumpNotSupported No description 226 160 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
90 0x31e3 0x06e0 LIM_WrongLimitId PP_InvalidSize No description 227 224 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
91 0x31ee 0x06e1 LIM_MonitorNotFound PP_InvalidAddress No description 238 225 LIMITS_IF HAS_MEMORY_IF fsfw/src/fsfw/monitoring/MonitoringIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
92 0x2901 0x06e2 TC_InvalidTargetState PP_InvalidContent No description 1 226 THERMAL_COMPONENT_IF HAS_MEMORY_IF fsfw/src/fsfw/thermal/ThermalComponentIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
93 0x29f1 0x06e3 TC_AboveOperationalLimit PP_UnalignedAccess No description 241 227 THERMAL_COMPONENT_IF HAS_MEMORY_IF fsfw/src/fsfw/thermal/ThermalComponentIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
94 0x29f2 0x06e4 TC_BelowOperationalLimit PP_WriteProtected No description 242 228 THERMAL_COMPONENT_IF HAS_MEMORY_IF fsfw/src/fsfw/thermal/ThermalComponentIF.h fsfw/src/fsfw/memory/HasMemoryIF.h
95 0x13e0 MH_UnknownCmd No description 224 MEMORY_HELPER fsfw/src/fsfw/memory/MemoryHelper.h
96 0x13e1 MH_InvalidAddress No description 225 MEMORY_HELPER fsfw/src/fsfw/memory/MemoryHelper.h
97 0x13e2 MH_InvalidSize No description 226 MEMORY_HELPER fsfw/src/fsfw/memory/MemoryHelper.h
98 0x13e3 MH_StateMismatch No description 227 MEMORY_HELPER fsfw/src/fsfw/memory/MemoryHelper.h
99 0x0601 0x38a1 PP_DoItMyself SGP4_InvalidEccentricity No description 1 161 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
100 0x0602 0x38a2 PP_PointsToVariable SGP4_InvalidMeanMotion No description 2 162 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
101 0x0603 0x38a3 PP_PointsToMemory SGP4_InvalidPerturbationElements No description 3 163 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
102 0x0604 0x38a4 PP_ActivityCompleted SGP4_InvalidSemiLatusRectum No description 4 164 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
103 0x0605 0x38a5 PP_PointsToVectorUint8 SGP4_InvalidEpochElements No description 5 165 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
104 0x0606 0x38a6 PP_PointsToVectorUint16 SGP4_SatelliteHasDecayed No description 6 166 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
105 0x0607 0x38b1 PP_PointsToVectorUint32 SGP4_TleTooOld No description 7 177 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
106 0x0608 0x38b2 PP_PointsToVectorFloat SGP4_TleNotInitialized No description 8 178 HAS_MEMORY_IF SGP4PROPAGATOR_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/coordinates/Sgp4Propagator.h
107 0x06a0 0x1801 PP_DumpNotSupported FF_Full No description 160 1 HAS_MEMORY_IF FIFO_CLASS fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/container/FIFOBase.h
108 0x1802 FF_Empty 2 FIFO_CLASS fsfw/src/fsfw/container/FIFOBase.h
109 0x1601 FMM_MapFull 1 FIXED_MULTIMAP fsfw/src/fsfw/container/FixedOrderedMultimap.h
110 0x1602 FMM_KeyDoesNotExist 2 FIXED_MULTIMAP fsfw/src/fsfw/container/FixedOrderedMultimap.h
111 0x3901 MUX_NotEnoughResources 1 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
112 0x3902 MUX_InsufficientMemory 2 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
113 0x3903 MUX_NoPrivilege 3 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
114 0x3904 MUX_WrongAttributeSetting 4 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
115 0x3905 MUX_MutexAlreadyLocked 5 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
116 0x3906 MUX_MutexNotFound 6 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
117 0x3907 MUX_MutexMaxLocks 7 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
118 0x3908 MUX_CurrThreadAlreadyOwnsMutex 8 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
119 0x3909 MUX_CurrThreadDoesNotOwnMutex 9 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
120 0x390a MUX_MutexTimeout 10 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
121 0x390b MUX_MutexInvalidId 11 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
122 0x390c MUX_MutexDestroyedWhileWaiting 12 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
123 0x3a01 MQI_Empty 1 MESSAGE_QUEUE_IF fsfw/src/fsfw/ipc/MessageQueueIF.h
124 0x3a02 MQI_Full No space left for more messages 2 MESSAGE_QUEUE_IF fsfw/src/fsfw/ipc/MessageQueueIF.h
125 0x3a03 MQI_NoReplyPartner Returned if a reply method was called without partner 3 MESSAGE_QUEUE_IF fsfw/src/fsfw/ipc/MessageQueueIF.h
126 0x3a04 MQI_DestinationInvalid Returned if the target destination is invalid. 4 MESSAGE_QUEUE_IF fsfw/src/fsfw/ipc/MessageQueueIF.h
127 0x0f01 CM_UnknownCommand 1 COMMAND_MESSAGE fsfw/src/fsfw/ipc/CommandMessageIF.h
128 0x06e0 0x0e01 PP_InvalidSize HM_InvalidMode No description 224 1 HAS_MEMORY_IF HAS_MODES_IF fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/modes/HasModesIF.h
129 0x06e1 0x0e02 PP_InvalidAddress HM_TransNotAllowed No description 225 2 HAS_MEMORY_IF HAS_MODES_IF fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/modes/HasModesIF.h
130 0x06e2 0x0e03 PP_InvalidContent HM_InTransition No description 226 3 HAS_MEMORY_IF HAS_MODES_IF fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/modes/HasModesIF.h
131 0x06e3 0x0e04 PP_UnalignedAccess HM_InvalidSubmode No description 227 4 HAS_MEMORY_IF HAS_MODES_IF fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/modes/HasModesIF.h
132 0x06e4 0x0c02 PP_WriteProtected MS_InvalidEntry No description 228 2 HAS_MEMORY_IF MODE_STORE_IF fsfw/src/fsfw/memory/HasMemoryIF.h fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
133 0x4c00 0x0c03 SPPA_NoPacketFound MS_TooManyElements No description 0 3 SPACE_PACKET_PARSER MODE_STORE_IF fsfw/src/fsfw/tmtcservices/SpacePacketParser.h fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
134 0x4c01 0x0c04 SPPA_SplitPacket MS_CantStoreEmpty No description 1 4 SPACE_PACKET_PARSER MODE_STORE_IF fsfw/src/fsfw/tmtcservices/SpacePacketParser.h fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h
135 0x1d01 0x0b01 ATC_ActivityStarted SB_ChildNotFound No description 1 ACCEPTS_TELECOMMANDS_IF SUBSYSTEM_BASE fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h fsfw/src/fsfw/subsystem/SubsystemBase.h
136 0x1d02 0x0b02 ATC_InvalidSubservice SB_ChildInfoUpdated No description 2 ACCEPTS_TELECOMMANDS_IF SUBSYSTEM_BASE fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h fsfw/src/fsfw/subsystem/SubsystemBase.h
137 0x1d03 0x0b03 ATC_IllegalApplicationData SB_ChildDoesntHaveModes No description 3 ACCEPTS_TELECOMMANDS_IF SUBSYSTEM_BASE fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h fsfw/src/fsfw/subsystem/SubsystemBase.h
138 0x1d04 0x0b04 ATC_SendTmFailed SB_CouldNotInsertChild No description 4 ACCEPTS_TELECOMMANDS_IF SUBSYSTEM_BASE fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h fsfw/src/fsfw/subsystem/SubsystemBase.h
139 0x1d05 0x0b05 ATC_Timeout SB_TableContainsInvalidObjectId No description 5 ACCEPTS_TELECOMMANDS_IF SUBSYSTEM_BASE fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h fsfw/src/fsfw/subsystem/SubsystemBase.h
140 0x2001 0x0d01 CSB_ExecutionComplete SS_SequenceAlreadyExists No description 1 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
141 0x2002 0x0d02 CSB_NoStepMessage SS_TableAlreadyExists No description 2 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
142 0x2003 0x0d03 CSB_ObjectBusy SS_TableDoesNotExist No description 3 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
143 0x2004 0x0d04 CSB_Busy SS_TableOrSequenceLengthInvalid No description 4 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
144 0x2005 0x0d05 CSB_InvalidTc SS_SequenceDoesNotExist No description 5 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
145 0x2006 0x0d06 CSB_InvalidObject SS_TableContainsInvalidObjectId No description 6 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
146 0x2007 0x0d07 CSB_InvalidReply SS_FallbackSequenceDoesNotExist No description 7 COMMAND_SERVICE_BASE SUBSYSTEM fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h fsfw/src/fsfw/subsystem/Subsystem.h
147 0x3da0 0x0d08 PVA_InvalidReadWriteMode SS_NoTargetTable No description 160 8 POOL_VARIABLE_IF SUBSYSTEM fsfw/src/fsfw/datapool/PoolVariableIF.h fsfw/src/fsfw/subsystem/Subsystem.h
148 0x3da1 0x0d09 PVA_InvalidPoolEntry SS_SequenceOrTableTooLong No description 161 9 POOL_VARIABLE_IF SUBSYSTEM fsfw/src/fsfw/datapool/PoolVariableIF.h fsfw/src/fsfw/subsystem/Subsystem.h
149 0x0801 0x0d0b DPS_InvalidParameterDefinition SS_IsFallbackSequence No description 1 11 DATA_SET_CLASS SUBSYSTEM fsfw/src/fsfw/datapool/DataSetIF.h fsfw/src/fsfw/subsystem/Subsystem.h
150 0x0802 0x0d0c DPS_SetWasAlreadyRead SS_AccessDenied No description 2 12 DATA_SET_CLASS SUBSYSTEM fsfw/src/fsfw/datapool/DataSetIF.h fsfw/src/fsfw/subsystem/Subsystem.h
151 0x0803 0x0d0e DPS_CommitingWithoutReading SS_TableInUse No description 3 14 DATA_SET_CLASS SUBSYSTEM fsfw/src/fsfw/datapool/DataSetIF.h fsfw/src/fsfw/subsystem/Subsystem.h
152 0x0804 0x0da1 DPS_DataSetUninitialised SS_TargetTableNotReached No description 4 161 DATA_SET_CLASS SUBSYSTEM fsfw/src/fsfw/datapool/DataSetIF.h fsfw/src/fsfw/subsystem/Subsystem.h
153 0x0805 0x0da2 DPS_DataSetFull SS_TableCheckFailed No description 5 162 DATA_SET_CLASS SUBSYSTEM fsfw/src/fsfw/datapool/DataSetIF.h fsfw/src/fsfw/subsystem/Subsystem.h
154 0x0806 0x2501 DPS_PoolVarNull EV_ListenerNotFound No description 6 1 DATA_SET_CLASS EVENT_MANAGER_IF fsfw/src/fsfw/datapool/DataSetIF.h fsfw/src/fsfw/events/EventManagerIF.h
0x3a01 MQI_Empty No description 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 No description 1 COMMAND_MESSAGE fsfw/src/fsfw/ipc/CommandMessageIF.h
0x3901 MUX_NotEnoughResources No description 1 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3902 MUX_InsufficientMemory No description 2 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3903 MUX_NoPrivilege No description 3 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3904 MUX_WrongAttributeSetting No description 4 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3905 MUX_MutexAlreadyLocked No description 5 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3906 MUX_MutexNotFound No description 6 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3907 MUX_MutexMaxLocks No description 7 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3908 MUX_CurrThreadAlreadyOwnsMutex No description 8 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x3909 MUX_CurrThreadDoesNotOwnMutex No description 9 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x390a MUX_MutexTimeout No description 10 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x390b MUX_MutexInvalidId No description 11 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x390c MUX_MutexDestroyedWhileWaiting No description 12 MUTEX_IF fsfw/src/fsfw/ipc/MutexIF.h
0x1601 FMM_MapFull No description 1 FIXED_MULTIMAP fsfw/src/fsfw/container/FixedOrderedMultimap.h
0x1602 FMM_KeyDoesNotExist No description 2 FIXED_MULTIMAP fsfw/src/fsfw/container/FixedOrderedMultimap.h
0x1801 FF_Full No description 1 FIFO_CLASS fsfw/src/fsfw/container/FIFOBase.h
0x1802 FF_Empty No description 2 FIFO_CLASS fsfw/src/fsfw/container/FIFOBase.h
0x03a0 DHB_InvalidChannel No description 160 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03b0 DHB_AperiodicReply No description 176 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03b1 DHB_IgnoreReplyData No description 177 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03b2 DHB_IgnoreFullPacket No description 178 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03c0 DHB_NothingToSend No description 192 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03c2 DHB_CommandMapError No description 194 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03d0 DHB_NoSwitch No description 208 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03e0 DHB_ChildTimeout No description 224 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x03e1 DHB_SwitchFailed No description 225 DEVICE_HANDLER_BASE fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
0x1201 AB_NeedSecondStep No description 1 ASSEMBLY_BASE fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x1202 AB_NeedToReconfigure No description 2 ASSEMBLY_BASE fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x1203 AB_ModeFallback No description 3 ASSEMBLY_BASE fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x1204 AB_ChildNotCommandable No description 4 ASSEMBLY_BASE fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x1205 AB_NeedToChangeHealth No description 5 ASSEMBLY_BASE fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x12a1 AB_NotEnoughChildrenInCorrectState No description 161 ASSEMBLY_BASE fsfw/src/fsfw/devicehandlers/AssemblyBase.h
0x27a0 DHI_NoCommandData No description 160 DEVICE_HANDLER_IF fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
0x27a1 DHI_CommandNotSupported No description 161 DEVICE_HANDLER_IF fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
0x27a2 DHI_CommandAlreadySent No description 162 DEVICE_HANDLER_IF fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
0x27a3 DHI_CommandWasNotSent No description 163 DEVICE_HANDLER_IF fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
155 0x27a4 0x04e1 DHI_CantSwitchAddress RMP_CommandNoDescriptorsAvailable No description 164 225 DEVICE_HANDLER_IF RMAP_CHANNEL fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h fsfw/src/fsfw/rmap/RMAP.h
156 0x27a5 0x04e2 DHI_WrongModeForCommand RMP_CommandBufferFull No description 165 226 DEVICE_HANDLER_IF RMAP_CHANNEL fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h fsfw/src/fsfw/rmap/RMAP.h
157 0x27a6 0x04e3 DHI_Timeout RMP_CommandChannelOutOfRange No description 166 227 DEVICE_HANDLER_IF RMAP_CHANNEL fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h fsfw/src/fsfw/rmap/RMAP.h
192 0x3609 0x040a CFDP_FilestoreResponseCantParseFsMessage RMP_ReplyCommandNotImplementedOrNotAuthorised No description 9 10 CFDP RMAP_CHANNEL fsfw/src/fsfw/cfdp/definitions.h fsfw/src/fsfw/rmap/RMAP.h
193 0x360a 0x040b CFDP_InvalidPduFormat RMP_ReplyRmwDataLengthError No description 10 11 CFDP RMAP_CHANNEL fsfw/src/fsfw/cfdp/definitions.h fsfw/src/fsfw/rmap/RMAP.h
194 0x04e1 0x040c RMP_CommandNoDescriptorsAvailable RMP_ReplyInvalidTargetLogicalAddress No description 225 12 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
195 0x04e2 0x1401 RMP_CommandBufferFull SE_BufferTooShort No description 226 1 RMAP_CHANNEL SERIALIZE_IF fsfw/src/fsfw/rmap/RMAP.h fsfw/src/fsfw/serialize/SerializeIF.h
196 0x04e3 0x1402 RMP_CommandChannelOutOfRange SE_StreamTooShort No description 227 2 RMAP_CHANNEL SERIALIZE_IF fsfw/src/fsfw/rmap/RMAP.h fsfw/src/fsfw/serialize/SerializeIF.h
197 0x04e6 0x1403 RMP_CommandChannelDeactivated SE_TooManyElements No description 230 3 RMAP_CHANNEL SERIALIZE_IF fsfw/src/fsfw/rmap/RMAP.h fsfw/src/fsfw/serialize/SerializeIF.h
0x04e7 RMP_CommandPortOutOfRange No description 231 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04e8 RMP_CommandPortInUse No description 232 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04e9 RMP_CommandNoChannel No description 233 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04ea RMP_NoHwCrc No description 234 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04d0 RMP_ReplyNoReply No description 208 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04d1 RMP_ReplyNotSent No description 209 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04d2 RMP_ReplyNotYetSent No description 210 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04d3 RMP_ReplyMissmatch No description 211 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04d4 RMP_ReplyTimeout No description 212 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04c0 RMP_ReplyInterfaceBusy No description 192 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04c1 RMP_ReplyTransmissionError No description 193 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04c2 RMP_ReplyInvalidData No description 194 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04c3 RMP_ReplyNotSupported No description 195 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f0 RMP_LinkDown No description 240 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f1 RMP_SpwCredit No description 241 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f2 RMP_SpwEscape No description 242 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f3 RMP_SpwDisconnect No description 243 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f4 RMP_SpwParity No description 244 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f5 RMP_SpwWriteSync No description 245 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f6 RMP_SpwInvalidAddress No description 246 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f7 RMP_SpwEarlyEop No description 247 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f8 RMP_SpwDma No description 248 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x04f9 RMP_SpwLinkError No description 249 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0400 RMP_ReplyOk No description 0 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0401 RMP_ReplyGeneralErrorCode No description 1 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0402 RMP_ReplyUnusedPacketTypeOrCommandCode No description 2 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0403 RMP_ReplyInvalidKey No description 3 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0404 RMP_ReplyInvalidDataCrc No description 4 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0405 RMP_ReplyEarlyEop No description 5 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0406 RMP_ReplyTooMuchData No description 6 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0407 RMP_ReplyEep No description 7 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0408 RMP_ReplyReserved No description 8 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x0409 RMP_ReplyVerifyBufferOverrun No description 9 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x040a RMP_ReplyCommandNotImplementedOrNotAuthorised No description 10 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x040b RMP_ReplyRmwDataLengthError No description 11 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x040c RMP_ReplyInvalidTargetLogicalAddress No description 12 RMAP_CHANNEL fsfw/src/fsfw/rmap/RMAP.h
0x3b01 SPH_SemaphoreTimeout No description 1 SEMAPHORE_IF fsfw/src/fsfw/tasks/SemaphoreIF.h
0x3b02 SPH_SemaphoreNotOwned No description 2 SEMAPHORE_IF fsfw/src/fsfw/tasks/SemaphoreIF.h
0x3b03 SPH_SemaphoreInvalid No description 3 SEMAPHORE_IF fsfw/src/fsfw/tasks/SemaphoreIF.h
0x0e01 HM_InvalidMode No description 1 HAS_MODES_IF fsfw/src/fsfw/modes/HasModesIF.h
0x0e02 HM_TransNotAllowed No description 2 HAS_MODES_IF fsfw/src/fsfw/modes/HasModesIF.h
0x0e03 HM_InTransition No description 3 HAS_MODES_IF fsfw/src/fsfw/modes/HasModesIF.h
0x0e04 HM_InvalidSubmode No description 4 HAS_MODES_IF fsfw/src/fsfw/modes/HasModesIF.h
0x2101 TMB_Busy No description 1 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2102 TMB_Full No description 2 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2103 TMB_Empty No description 3 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2104 TMB_NullRequested No description 4 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2105 TMB_TooLarge No description 5 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2106 TMB_NotReady No description 6 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2107 TMB_DumpError No description 7 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2108 TMB_CrcError No description 8 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2109 TMB_Timeout No description 9 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210a TMB_IdlePacketFound No description 10 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210b TMB_TelecommandFound No description 11 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210c TMB_NoPusATm No description 12 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210d TMB_TooSmall No description 13 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210e TMB_BlockNotFound No description 14 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x210f TMB_InvalidRequest No description 15 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
0x2201 TMF_Busy No description 1 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2202 TMF_LastPacketFound No description 2 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2203 TMF_StopFetch No description 3 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2204 TMF_Timeout No description 4 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2205 TMF_TmChannelFull No description 5 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2206 TMF_NotStored No description 6 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2207 TMF_AllDeleted No description 7 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2208 TMF_InvalidData No description 8 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x2209 TMF_NotReady No description 9 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
0x1e00 PUS_InvalidPusVersion No description 0 PUS_IF fsfw/src/fsfw/tmtcpacket/pus/PusIF.h
0x1e01 PUS_InvalidCrc16 No description 1 PUS_IF fsfw/src/fsfw/tmtcpacket/pus/PusIF.h
0x2501 EV_ListenerNotFound No description 1 EVENT_MANAGER_IF fsfw/src/fsfw/events/EventManagerIF.h
0x1000 TIM_UnsupportedTimeFormat No description 0 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
0x1001 TIM_NotEnoughInformationForTargetFormat No description 1 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
0x1002 TIM_LengthMismatch No description 2 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
0x1003 TIM_InvalidTimeFormat No description 3 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
0x1004 TIM_InvalidDayOfYear No description 4 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
0x1005 TIM_TimeDoesNotFitFormat No description 5 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
0x3701 TSI_BadTimestamp No description 1 TIME_STAMPER_IF fsfw/src/fsfw/timemanager/TimeStampIF.h
0x3001 POS_InPowerTransition No description 1 POWER_SWITCHER fsfw/src/fsfw/power/PowerSwitcher.h
0x3002 POS_SwitchStateMismatch No description 2 POWER_SWITCHER fsfw/src/fsfw/power/PowerSwitcher.h
0x0501 PS_SwitchOn No description 1 POWER_SWITCH_IF fsfw/src/fsfw/power/PowerSwitchIF.h
0x0500 PS_SwitchOff No description 0 POWER_SWITCH_IF fsfw/src/fsfw/power/PowerSwitchIF.h
0x0502 PS_SwitchTimeout No description 2 POWER_SWITCH_IF fsfw/src/fsfw/power/PowerSwitchIF.h
0x0503 PS_FuseOn No description 3 POWER_SWITCH_IF fsfw/src/fsfw/power/PowerSwitchIF.h
0x0504 PS_FuseOff No description 4 POWER_SWITCH_IF fsfw/src/fsfw/power/PowerSwitchIF.h
0x0201 OM_InsertionFailed No description 1 OBJECT_MANAGER_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h
0x0202 OM_NotFound No description 2 OBJECT_MANAGER_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h
198 0x0203 0x3da0 OM_ChildInitFailed PVA_InvalidReadWriteMode No description 3 160 OBJECT_MANAGER_IF POOL_VARIABLE_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h fsfw/src/fsfw/datapool/PoolVariableIF.h
199 0x0204 0x3da1 OM_InternalErrReporterUninit PVA_InvalidPoolEntry No description 4 161 OBJECT_MANAGER_IF POOL_VARIABLE_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h fsfw/src/fsfw/datapool/PoolVariableIF.h
200 0x2e01 0x0801 HPA_InvalidIdentifierId DPS_InvalidParameterDefinition No description 1 HAS_PARAMETERS_IF DATA_SET_CLASS fsfw/src/fsfw/parameters/HasParametersIF.h fsfw/src/fsfw/datapool/DataSetIF.h
203 0x2e05 0x0804 HPA_ReadOnly DPS_DataSetUninitialised No description 5 4 HAS_PARAMETERS_IF DATA_SET_CLASS fsfw/src/fsfw/parameters/HasParametersIF.h fsfw/src/fsfw/datapool/DataSetIF.h
204 0x2d01 0x0805 PAW_UnknownDatatype DPS_DataSetFull No description 1 5 PARAMETER_WRAPPER DATA_SET_CLASS fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/datapool/DataSetIF.h
205 0x2d02 0x0806 PAW_DatatypeMissmatch DPS_PoolVarNull No description 2 6 PARAMETER_WRAPPER DATA_SET_CLASS fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/datapool/DataSetIF.h
206 0x2d03 0x1c01 PAW_Readonly TCD_PacketLost No description 3 1 PARAMETER_WRAPPER PACKET_DISTRIBUTION fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
207 0x2d04 0x1c02 PAW_TooBig TCD_DestinationNotFound No description 4 2 PARAMETER_WRAPPER PACKET_DISTRIBUTION fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
208 0x2d05 0x1c03 PAW_SourceNotSet TCD_ServiceIdAlreadyExists No description 5 3 PARAMETER_WRAPPER PACKET_DISTRIBUTION fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
209 0x2d06 0x1b00 PAW_OutOfBounds TCC_NoDestinationFound No description 6 0 PARAMETER_WRAPPER TMTC_DISTRIBUTION fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/tcdistribution/definitions.h
210 0x2d07 0x1b01 PAW_NotSet TCC_InvalidCcsdsVersion No description 7 1 PARAMETER_WRAPPER TMTC_DISTRIBUTION fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/tcdistribution/definitions.h
211 0x2d08 0x1b02 PAW_ColumnOrRowsZero TCC_InvalidApid No description 8 2 PARAMETER_WRAPPER TMTC_DISTRIBUTION fsfw/src/fsfw/parameters/ParameterWrapper.h fsfw/src/fsfw/tcdistribution/definitions.h
212 0x2401 0x1b03 MT_TooDetailedRequest TCC_InvalidPacketType No description 1 3 MATCH_TREE_CLASS TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/matching/MatchTree.h fsfw/src/fsfw/tcdistribution/definitions.h
213 0x2402 0x1b04 MT_TooGeneralRequest TCC_InvalidSecHeaderField No description 2 4 MATCH_TREE_CLASS TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/matching/MatchTree.h fsfw/src/fsfw/tcdistribution/definitions.h
214 0x2403 0x1b05 MT_NoMatch TCC_IncorrectPrimaryHeader No description 3 5 MATCH_TREE_CLASS TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/matching/MatchTree.h fsfw/src/fsfw/tcdistribution/definitions.h
215 0x2404 0x1b07 MT_Full TCC_IncompletePacket No description 4 7 MATCH_TREE_CLASS TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/matching/MatchTree.h fsfw/src/fsfw/tcdistribution/definitions.h
216 0x2405 0x1b08 MT_NewNodeCreated TCC_InvalidPusVersion No description 5 8 MATCH_TREE_CLASS TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/matching/MatchTree.h fsfw/src/fsfw/tcdistribution/definitions.h
217 0x3f01 0x1b09 DLEE_NoPacketFound TCC_IncorrectChecksum No description 1 9 DLE_ENCODER TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/DleParser.h fsfw/src/fsfw/tcdistribution/definitions.h
218 0x3f02 0x1b0a DLEE_PossiblePacketLoss TCC_IllegalPacketSubtype No description 2 10 DLE_ENCODER TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/DleParser.h fsfw/src/fsfw/tcdistribution/definitions.h
219 0x2f01 0x1b0b ASC_TooLongForTargetType TCC_IncorrectSecondaryHeader No description 1 11 ASCII_CONVERTER TMTC_DISTRIBUTION fsfw/src/fsfw/globalfunctions/AsciiConverter.h fsfw/src/fsfw/tcdistribution/definitions.h
0x2f02 ASC_InvalidCharacters No description 2 ASCII_CONVERTER fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x2f03 ASC_BufferTooSmall No description 3 ASCII_CONVERTER fsfw/src/fsfw/globalfunctions/AsciiConverter.h
0x1c01 TCD_PacketLost No description 1 PACKET_DISTRIBUTION fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1c02 TCD_DestinationNotFound No description 2 PACKET_DISTRIBUTION fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1c03 TCD_ServiceIdAlreadyExists No description 3 PACKET_DISTRIBUTION fsfw/src/fsfw/tcdistribution/TcDistributorBase.h
0x1b00 TCC_NoDestinationFound No description 0 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b01 TCC_InvalidCcsdsVersion No description 1 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b02 TCC_InvalidApid No description 2 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b03 TCC_InvalidPacketType No description 3 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b04 TCC_InvalidSecHeaderField No description 4 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b05 TCC_IncorrectPrimaryHeader No description 5 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b07 TCC_IncompletePacket No description 7 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b08 TCC_InvalidPusVersion No description 8 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b09 TCC_IncorrectChecksum No description 9 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
0x1b0a TCC_IllegalPacketSubtype No description 10 TMTC_DISTRIBUTION fsfw/src/fsfw/tcdistribution/definitions.h
220 0x1b0b 0x3001 TCC_IncorrectSecondaryHeader POS_InPowerTransition No description 11 1 TMTC_DISTRIBUTION POWER_SWITCHER fsfw/src/fsfw/tcdistribution/definitions.h fsfw/src/fsfw/power/PowerSwitcher.h
221 0x1701 0x3002 HHI_ObjectNotHealthy POS_SwitchStateMismatch No description 1 2 HAS_HEALTH_IF POWER_SWITCHER fsfw/src/fsfw/health/HasHealthIF.h fsfw/src/fsfw/power/PowerSwitcher.h
222 0x1702 0x0501 HHI_InvalidHealthState PS_SwitchOn No description 2 1 HAS_HEALTH_IF POWER_SWITCH_IF fsfw/src/fsfw/health/HasHealthIF.h fsfw/src/fsfw/power/PowerSwitchIF.h
224 0x0c02 0x0502 MS_InvalidEntry PS_SwitchTimeout No description 2 MODE_STORE_IF POWER_SWITCH_IF fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h fsfw/src/fsfw/power/PowerSwitchIF.h
225 0x0c03 0x0503 MS_TooManyElements PS_FuseOn No description 3 MODE_STORE_IF POWER_SWITCH_IF fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h fsfw/src/fsfw/power/PowerSwitchIF.h
226 0x0c04 0x0504 MS_CantStoreEmpty PS_FuseOff No description 4 MODE_STORE_IF POWER_SWITCH_IF fsfw/src/fsfw/subsystem/modes/ModeStoreIF.h fsfw/src/fsfw/power/PowerSwitchIF.h
227 0x0d01 0x3b00 SS_SequenceAlreadyExists SPH_ConnBroken No description 1 0 SUBSYSTEM SEMAPHORE_IF fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/common/TcpTmTcServer.h
228 0x0d02 0x2a01 SS_TableAlreadyExists IEC_NoConfigurationTable No description 2 1 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
229 0x0d03 0x2a02 SS_TableDoesNotExist IEC_NoCpuTable No description 3 2 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
230 0x0d04 0x2a03 SS_TableOrSequenceLengthInvalid IEC_InvalidWorkspaceAddress No description 4 3 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
231 0x0d05 0x2a04 SS_SequenceDoesNotExist IEC_TooLittleWorkspace No description 5 4 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
232 0x0d06 0x2a05 SS_TableContainsInvalidObjectId IEC_WorkspaceAllocation No description 6 5 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
233 0x0d07 0x2a06 SS_FallbackSequenceDoesNotExist IEC_InterruptStackTooSmall No description 7 6 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
234 0x0d08 0x2a07 SS_NoTargetTable IEC_ThreadExitted No description 8 7 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
235 0x0d09 0x2a08 SS_SequenceOrTableTooLong IEC_InconsistentMpInformation No description 9 8 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
236 0x0d0b 0x2a09 SS_IsFallbackSequence IEC_InvalidNode No description 11 9 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
237 0x0d0c 0x2a0a SS_AccessDenied IEC_NoMpci No description 12 10 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
238 0x0d0e 0x2a0b SS_TableInUse IEC_BadPacket No description 14 11 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
239 0x0da1 0x2a0c SS_TargetTableNotReached IEC_OutOfPackets No description 161 12 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
240 0x0da2 0x2a0d SS_TableCheckFailed IEC_OutOfGlobalObjects No description 162 13 SUBSYSTEM INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/Subsystem.h fsfw/src/fsfw/osal/InternalErrorCodes.h
241 0x0b01 0x2a0e SB_ChildNotFound IEC_OutOfProxies No description 1 14 SUBSYSTEM_BASE INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/SubsystemBase.h fsfw/src/fsfw/osal/InternalErrorCodes.h
242 0x0b02 0x2a0f SB_ChildInfoUpdated IEC_InvalidGlobalId No description 2 15 SUBSYSTEM_BASE INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/SubsystemBase.h fsfw/src/fsfw/osal/InternalErrorCodes.h
243 0x0b03 0x2a10 SB_ChildDoesntHaveModes IEC_BadStackHook No description 3 16 SUBSYSTEM_BASE INTERNAL_ERROR_CODES fsfw/src/fsfw/subsystem/SubsystemBase.h fsfw/src/fsfw/osal/InternalErrorCodes.h
244 0x2a11 IEC_BadAttributes 17 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
245 0x2a12 IEC_ImplementationKeyCreateInconsistency 18 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
246 0x2a13 IEC_ImplementationBlockingOperationCancel 19 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
247 0x2a14 IEC_MutexObtainFromBadState 20 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
248 0x2a15 IEC_UnlimitedAndMaximumIs0 21 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
249 0x2600 FDI_YourFault 0 HANDLES_FAILURES_IF fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h
250 0x2601 FDI_MyFault 1 HANDLES_FAILURES_IF fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h
251 0x2602 FDI_ConfirmLater 2 HANDLES_FAILURES_IF fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h
252 0x1e00 PUS_InvalidPusVersion 0 PUS_IF fsfw/src/fsfw/tmtcpacket/pus/PusIF.h
253 0x1e01 PUS_InvalidCrc16 1 PUS_IF fsfw/src/fsfw/tmtcpacket/pus/PusIF.h
254 0x0201 OM_InsertionFailed 1 OBJECT_MANAGER_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h
255 0x0202 OM_NotFound 2 OBJECT_MANAGER_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h
256 0x0203 OM_ChildInitFailed 3 OBJECT_MANAGER_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h
257 0x0204 OM_InternalErrReporterUninit 4 OBJECT_MANAGER_IF fsfw/src/fsfw/objectmanager/ObjectManagerIF.h
258 0x2201 TMF_Busy 1 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
259 0x2202 TMF_LastPacketFound 2 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
260 0x2203 TMF_StopFetch 3 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
261 0x2204 TMF_Timeout 4 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
262 0x2205 TMF_TmChannelFull 5 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
263 0x2206 TMF_NotStored 6 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
264 0x2207 TMF_AllDeleted 7 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
265 0x2208 TMF_InvalidData 8 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
266 0x2209 TMF_NotReady 9 TM_STORE_FRONTEND_IF fsfw/src/fsfw/tmstorage/TmStoreFrontendIF.h
267 0x2101 TMB_Busy 1 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
268 0x2102 TMB_Full 2 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
269 0x2103 TMB_Empty 3 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
270 0x2104 TMB_NullRequested 4 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
271 0x2105 TMB_TooLarge 5 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
272 0x2106 TMB_NotReady 6 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
273 0x2107 TMB_DumpError 7 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
274 0x2108 TMB_CrcError 8 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
275 0x2109 TMB_Timeout 9 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
276 0x210a TMB_IdlePacketFound 10 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
277 0x210b TMB_TelecommandFound 11 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
278 0x210c TMB_NoPusATm 12 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
279 0x210d TMB_TooSmall 13 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
280 0x210e TMB_BlockNotFound 14 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
281 0x210f TMB_InvalidRequest 15 TM_STORE_BACKEND_IF fsfw/src/fsfw/tmstorage/TmStoreBackendIF.h
282 0x2d01 PAW_UnknownDatatype 1 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
283 0x2d02 PAW_DatatypeMissmatch 2 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
284 0x2d03 PAW_Readonly 3 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
285 0x2d04 PAW_TooBig 4 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
286 0x2d05 PAW_SourceNotSet 5 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
287 0x2d06 PAW_OutOfBounds 6 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
288 0x2d07 PAW_NotSet 7 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
289 0x2d08 PAW_ColumnOrRowsZero 8 PARAMETER_WRAPPER fsfw/src/fsfw/parameters/ParameterWrapper.h
290 0x2e01 HPA_InvalidIdentifierId 1 HAS_PARAMETERS_IF fsfw/src/fsfw/parameters/HasParametersIF.h
291 0x2e02 HPA_InvalidDomainId 2 HAS_PARAMETERS_IF fsfw/src/fsfw/parameters/HasParametersIF.h
292 0x2e03 HPA_InvalidValue 3 HAS_PARAMETERS_IF fsfw/src/fsfw/parameters/HasParametersIF.h
293 0x2e05 HPA_ReadOnly 5 HAS_PARAMETERS_IF fsfw/src/fsfw/parameters/HasParametersIF.h
294 0x3b01 SPH_SemaphoreTimeout 1 SEMAPHORE_IF fsfw/src/fsfw/tasks/SemaphoreIF.h
295 0x3b02 SPH_SemaphoreNotOwned 2 SEMAPHORE_IF fsfw/src/fsfw/tasks/SemaphoreIF.h
296 0x3b03 SPH_SemaphoreInvalid 3 SEMAPHORE_IF fsfw/src/fsfw/tasks/SemaphoreIF.h
297 0x0b04 0x1a01 SB_CouldNotInsertChild TRC_NotEnoughSensors No description 4 1 SUBSYSTEM_BASE TRIPLE_REDUNDACY_CHECK fsfw/src/fsfw/subsystem/SubsystemBase.h fsfw/src/fsfw/monitoring/TriplexMonitor.h
298 0x0b05 0x1a02 SB_TableContainsInvalidObjectId TRC_LowestValueOol No description 5 2 SUBSYSTEM_BASE TRIPLE_REDUNDACY_CHECK fsfw/src/fsfw/subsystem/SubsystemBase.h fsfw/src/fsfw/monitoring/TriplexMonitor.h
299 0x3e00 0x1a03 HKM_QueueOrDestinationInvalid TRC_HighestValueOol No description 0 3 HOUSEKEEPING_MANAGER TRIPLE_REDUNDACY_CHECK fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h fsfw/src/fsfw/monitoring/TriplexMonitor.h
312 0x4305 0x31e2 FILS_InvalidParameters LIM_WrongPid No description 5 226 FILE_SYSTEM LIMITS_IF fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/monitoring/MonitoringIF.h
313 0x430a 0x31e3 FILS_FileDoesNotExist LIM_WrongLimitId No description 10 227 FILE_SYSTEM LIMITS_IF fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/monitoring/MonitoringIF.h
314 0x430b 0x31ee FILS_FileAlreadyExists LIM_MonitorNotFound No description 11 238 FILE_SYSTEM LIMITS_IF fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/monitoring/MonitoringIF.h
315 0x3601 CFDP_InvalidTlvType 1 CFDP fsfw/src/fsfw/cfdp/definitions.h
316 0x3602 CFDP_InvalidDirectiveField 2 CFDP fsfw/src/fsfw/cfdp/definitions.h
317 0x3603 CFDP_InvalidPduDatafieldLen 3 CFDP fsfw/src/fsfw/cfdp/definitions.h
318 0x3604 CFDP_InvalidAckDirectiveFields 4 CFDP fsfw/src/fsfw/cfdp/definitions.h
319 0x3605 CFDP_MetadataCantParseOptions 5 CFDP fsfw/src/fsfw/cfdp/definitions.h
320 0x3606 CFDP_NakCantParseOptions 6 CFDP fsfw/src/fsfw/cfdp/definitions.h
321 0x3607 CFDP_FinishedCantParseFsResponses 7 CFDP fsfw/src/fsfw/cfdp/definitions.h
322 0x3608 CFDP_FilestoreRequiresSecondFile 8 CFDP fsfw/src/fsfw/cfdp/definitions.h
323 0x3609 CFDP_FilestoreResponseCantParseFsMessage 9 CFDP fsfw/src/fsfw/cfdp/definitions.h
324 0x360a CFDP_InvalidPduFormat 10 CFDP fsfw/src/fsfw/cfdp/definitions.h
325 0x4300 FILS_GenericFileError 0 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
326 0x4301 FILS_GenericDirError 1 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
327 0x4302 FILS_FilesystemInactive 2 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
328 0x4303 FILS_GenericRenameError 3 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
329 0x4304 FILS_IsBusy 4 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
330 0x4305 FILS_InvalidParameters 5 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
331 0x430a FILS_FileDoesNotExist 10 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
332 0x430b FILS_FileAlreadyExists 11 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
333 0x430c FILS_NotAFile 12 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
334 0x430d FILS_FileLocked 13 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
335 0x430e FILS_PermissionDenied 14 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
336 0x4315 FILS_DirectoryDoesNotExist 21 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
337 0x4316 FILS_DirectoryAlreadyExists 22 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
338 0x4317 FILS_NotADirectory 23 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
339 0x4318 FILS_DirectoryNotEmpty 24 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
340 0x431e FILS_SequencePacketMissingWrite 30 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
341 0x431f FILS_SequencePacketMissingRead 31 FILE_SYSTEM fsfw/src/fsfw/filesystem/HasFileSystemIF.h
342 0x2c01 CCS_BcIsSetVrCommand 1 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
343 0x2c02 CCS_BcIsUnlockCommand 2 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
344 0x2cb0 CCS_BcIllegalCommand 176 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
345 0x2cb1 CCS_BoardReadingNotFinished 177 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
346 0x2cf0 CCS_NsPositiveW 240 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
347 0x2cf1 CCS_NsNegativeW 241 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
348 0x2cf2 CCS_NsLockout 242 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
349 0x2cf3 CCS_FarmInLockout 243 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
350 0x2cf4 CCS_FarmInWait 244 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
351 0x2ce0 CCS_WrongSymbol 224 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
352 0x2ce1 CCS_DoubleStart 225 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
353 0x2ce2 CCS_StartSymbolMissed 226 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
354 0x2ce3 CCS_EndWithoutStart 227 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
355 0x2ce4 CCS_TooLarge 228 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
356 0x2ce5 CCS_TooShort 229 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
357 0x2ce6 CCS_WrongTfVersion 230 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
358 0x2ce7 CCS_WrongSpacecraftId 231 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
359 0x2ce8 CCS_NoValidFrameType 232 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
360 0x2ce9 CCS_CrcFailed 233 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
361 0x2cea CCS_VcNotFound 234 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
362 0x2ceb CCS_ForwardingFailed 235 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
363 0x2cec CCS_ContentTooLarge 236 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
364 0x2ced CCS_ResidualData 237 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
365 0x2cee CCS_DataCorrupted 238 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
366 0x2cef CCS_IllegalSegmentationFlag 239 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
367 0x2cd0 CCS_IllegalFlagCombination 208 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
368 0x2cd1 CCS_ShorterThanHeader 209 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
369 0x2cd2 CCS_TooShortBlockedPacket 210 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
370 0x2cd3 CCS_TooShortMapExtraction 211 CCSDS_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h
371 0x430c 0x4201 FILS_NotAFile PUS11_InvalidTypeTimeWindow No description 12 1 FILE_SYSTEM PUS_SERVICE_11 fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
372 0x430d 0x4202 FILS_FileLocked PUS11_InvalidTimeWindow No description 13 2 FILE_SYSTEM PUS_SERVICE_11 fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
373 0x430e 0x4203 FILS_PermissionDenied PUS11_TimeshiftingNotPossible No description 14 3 FILE_SYSTEM PUS_SERVICE_11 fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
374 0x4315 0x4204 FILS_DirectoryDoesNotExist PUS11_InvalidRelativeTime No description 21 4 FILE_SYSTEM PUS_SERVICE_11 fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
375 0x4316 0x4205 FILS_DirectoryAlreadyExists PUS11_ContainedTcTooSmall No description 22 5 FILE_SYSTEM PUS_SERVICE_11 fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
376 0x4317 0x4206 FILS_NotADirectory PUS11_ContainedTcCrcMissmatch No description 23 6 FILE_SYSTEM PUS_SERVICE_11 fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
377 0x4318 0x3401 FILS_DirectoryNotEmpty DC_NoReplyReceived No description 24 1 FILE_SYSTEM DEVICE_COMMUNICATION_IF fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
378 0x431e 0x3402 FILS_SequencePacketMissingWrite DC_ProtocolError No description 30 2 FILE_SYSTEM DEVICE_COMMUNICATION_IF fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
379 0x431f 0x3403 FILS_SequencePacketMissingRead DC_Nullpointer No description 31 3 FILE_SYSTEM DEVICE_COMMUNICATION_IF fsfw/src/fsfw/filesystem/HasFileSystemIF.h fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
380 0x4201 0x3404 PUS11_InvalidTypeTimeWindow DC_InvalidCookieType No description 1 4 PUS_SERVICE_11 DEVICE_COMMUNICATION_IF fsfw/src/fsfw/pus/Service11TelecommandScheduling.h fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
381 0x4202 0x3405 PUS11_InvalidTimeWindow DC_NotActive No description 2 5 PUS_SERVICE_11 DEVICE_COMMUNICATION_IF fsfw/src/fsfw/pus/Service11TelecommandScheduling.h fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
382 0x4203 0x3406 PUS11_TimeshiftingNotPossible DC_TooMuchData No description 3 6 PUS_SERVICE_11 DEVICE_COMMUNICATION_IF fsfw/src/fsfw/pus/Service11TelecommandScheduling.h fsfw/src/fsfw/devicehandlers/DeviceCommunicationIF.h
0x4204 PUS11_InvalidRelativeTime No description 4 PUS_SERVICE_11 fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4205 PUS11_ContainedTcTooSmall No description 5 PUS_SERVICE_11 fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4206 PUS11_ContainedTcCrcMissmatch No description 6 PUS_SERVICE_11 fsfw/src/fsfw/pus/Service11TelecommandScheduling.h
0x4100 PUS9_ConnBroken No description 0 PUS_SERVICE_9 fsfw/src/fsfw/osal/common/TcpTmTcServer.h
0x2a01 IEC_NoConfigurationTable No description 1 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a02 IEC_NoCpuTable No description 2 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a03 IEC_InvalidWorkspaceAddress No description 3 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a04 IEC_TooLittleWorkspace No description 4 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a05 IEC_WorkspaceAllocation No description 5 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a06 IEC_InterruptStackTooSmall No description 6 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a07 IEC_ThreadExitted No description 7 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a08 IEC_InconsistentMpInformation No description 8 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a09 IEC_InvalidNode No description 9 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a0a IEC_NoMpci No description 10 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a0b IEC_BadPacket No description 11 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a0c IEC_OutOfPackets No description 12 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a0d IEC_OutOfGlobalObjects No description 13 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
0x2a0e IEC_OutOfProxies No description 14 INTERNAL_ERROR_CODES fsfw/src/fsfw/osal/InternalErrorCodes.h
383 0x2a0f 0x03a0 IEC_InvalidGlobalId DHB_InvalidChannel No description 15 160 INTERNAL_ERROR_CODES DEVICE_HANDLER_BASE fsfw/src/fsfw/osal/InternalErrorCodes.h fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
384 0x2a10 0x03b0 IEC_BadStackHook DHB_AperiodicReply No description 16 176 INTERNAL_ERROR_CODES DEVICE_HANDLER_BASE fsfw/src/fsfw/osal/InternalErrorCodes.h fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
385 0x2a11 0x03b1 IEC_BadAttributes DHB_IgnoreReplyData No description 17 177 INTERNAL_ERROR_CODES DEVICE_HANDLER_BASE fsfw/src/fsfw/osal/InternalErrorCodes.h fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
389 0x2a15 0x03d0 IEC_UnlimitedAndMaximumIs0 DHB_NoSwitch No description 21 208 INTERNAL_ERROR_CODES DEVICE_HANDLER_BASE fsfw/src/fsfw/osal/InternalErrorCodes.h fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
390 0x1401 0x03e0 SE_BufferTooShort DHB_ChildTimeout No description 1 224 SERIALIZE_IF DEVICE_HANDLER_BASE fsfw/src/fsfw/serialize/SerializeIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
391 0x1402 0x03e1 SE_StreamTooShort DHB_SwitchFailed No description 2 225 SERIALIZE_IF DEVICE_HANDLER_BASE fsfw/src/fsfw/serialize/SerializeIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerBase.h
392 0x1403 0x1201 SE_TooManyElements AB_NeedSecondStep No description 3 1 SERIALIZE_IF ASSEMBLY_BASE fsfw/src/fsfw/serialize/SerializeIF.h fsfw/src/fsfw/devicehandlers/AssemblyBase.h
393 0x2600 0x1202 FDI_YourFault AB_NeedToReconfigure No description 0 2 HANDLES_FAILURES_IF ASSEMBLY_BASE fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h fsfw/src/fsfw/devicehandlers/AssemblyBase.h
394 0x2601 0x1203 FDI_MyFault AB_ModeFallback No description 1 3 HANDLES_FAILURES_IF ASSEMBLY_BASE fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h fsfw/src/fsfw/devicehandlers/AssemblyBase.h
395 0x2602 0x1204 FDI_ConfirmLater AB_ChildNotCommandable No description 2 4 HANDLES_FAILURES_IF ASSEMBLY_BASE fsfw/src/fsfw/fdir/ConfirmsFailuresIF.h fsfw/src/fsfw/devicehandlers/AssemblyBase.h
396 0x2c01 0x1205 CCS_BcIsSetVrCommand AB_NeedToChangeHealth No description 1 5 CCSDS_HANDLER_IF ASSEMBLY_BASE fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/AssemblyBase.h
397 0x2c02 0x12a1 CCS_BcIsUnlockCommand AB_NotEnoughChildrenInCorrectState No description 2 161 CCSDS_HANDLER_IF ASSEMBLY_BASE fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/AssemblyBase.h
398 0x2cb0 0x27a0 CCS_BcIllegalCommand DHI_NoCommandData No description 176 160 CCSDS_HANDLER_IF DEVICE_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
399 0x2cb1 0x27a1 CCS_BoardReadingNotFinished DHI_CommandNotSupported No description 177 161 CCSDS_HANDLER_IF DEVICE_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
400 0x2cf0 0x27a2 CCS_NsPositiveW DHI_CommandAlreadySent No description 240 162 CCSDS_HANDLER_IF DEVICE_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
416 0x2ceb 0x27c3 CCS_ForwardingFailed DHI_DeviceReplyInvalid No description 235 195 CCSDS_HANDLER_IF DEVICE_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
417 0x2cec 0x27d0 CCS_ContentTooLarge DHI_InvalidCommandParameter No description 236 208 CCSDS_HANDLER_IF DEVICE_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
418 0x2ced 0x27d1 CCS_ResidualData DHI_InvalidNumberOrLengthOfParameters No description 237 209 CCSDS_HANDLER_IF DEVICE_HANDLER_IF fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/devicehandlers/DeviceHandlerIF.h
419 0x2cee 0x2401 CCS_DataCorrupted MT_TooDetailedRequest No description 238 1 CCSDS_HANDLER_IF MATCH_TREE_CLASS fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
420 0x2cef 0x2402 CCS_IllegalSegmentationFlag MT_TooGeneralRequest No description 239 2 CCSDS_HANDLER_IF MATCH_TREE_CLASS fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
421 0x2cd0 0x2403 CCS_IllegalFlagCombination MT_NoMatch No description 208 3 CCSDS_HANDLER_IF MATCH_TREE_CLASS fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
422 0x2cd1 0x2404 CCS_ShorterThanHeader MT_Full No description 209 4 CCSDS_HANDLER_IF MATCH_TREE_CLASS fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
423 0x2cd2 0x2405 CCS_TooShortBlockedPacket MT_NewNodeCreated No description 210 5 CCSDS_HANDLER_IF MATCH_TREE_CLASS fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/globalfunctions/matching/MatchTree.h
424 0x2cd3 0x3f01 CCS_TooShortMapExtraction DLEE_NoPacketFound No description 211 1 CCSDS_HANDLER_IF DLE_ENCODER fsfw/src/fsfw/datalinklayer/CCSDSReturnValuesIF.h fsfw/src/fsfw/globalfunctions/DleParser.h
425 0x4500 0x3f02 HSPI_OpeningFileFailed DLEE_PossiblePacketLoss No description 0 2 HAL_SPI DLE_ENCODER fsfw/src/fsfw_hal/linux/spi/SpiComIF.h fsfw/src/fsfw/globalfunctions/DleParser.h
426 0x4501 0x2f01 HSPI_FullDuplexTransferFailed ASC_TooLongForTargetType No description 1 HAL_SPI ASCII_CONVERTER fsfw/src/fsfw_hal/linux/spi/SpiComIF.h fsfw/src/fsfw/globalfunctions/AsciiConverter.h
427 0x4502 0x2f02 HSPI_HalfDuplexTransferFailed ASC_InvalidCharacters No description 2 HAL_SPI ASCII_CONVERTER fsfw/src/fsfw_hal/linux/spi/SpiComIF.h fsfw/src/fsfw/globalfunctions/AsciiConverter.h
428 0x4801 0x2f03 HGIO_UnknownGpioId ASC_BufferTooSmall No description 1 3 HAL_GPIO ASCII_CONVERTER fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/globalfunctions/AsciiConverter.h
429 0x4802 0x1701 HGIO_DriveGpioFailure HHI_ObjectNotHealthy No description 2 1 HAL_GPIO HAS_HEALTH_IF fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/health/HasHealthIF.h
430 0x4803 0x1702 HGIO_GpioTypeFailure HHI_InvalidHealthState No description 3 2 HAL_GPIO HAS_HEALTH_IF fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/health/HasHealthIF.h
431 0x4804 0x1703 HGIO_GpioInvalidInstance HHI_IsExternallyControlled No description 4 3 HAL_GPIO HAS_HEALTH_IF fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/health/HasHealthIF.h
432 0x4805 0x3201 HGIO_GpioDuplicateDetected CF_ObjectHasNoFunctions No description 5 1 HAL_GPIO COMMANDS_ACTIONS_IF fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/action/CommandsActionsIF.h
433 0x4806 0x3202 HGIO_GpioInitFailed CF_AlreadyCommanding No description 6 2 HAL_GPIO COMMANDS_ACTIONS_IF fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/action/CommandsActionsIF.h
434 0x4807 0x3301 HGIO_GpioGetValueFailed HF_IsBusy No description 7 1 HAL_GPIO HAS_ACTIONS_IF fsfw/src/fsfw_hal/linux/gpio/LinuxLibgpioIF.h fsfw/src/fsfw/action/HasActionsIF.h
435 0x4601 0x3302 HURT_UartReadFailure HF_InvalidParameters No description 1 2 HAL_UART HAS_ACTIONS_IF fsfw/src/fsfw_hal/linux/serial/SerialComIF.h fsfw/src/fsfw/action/HasActionsIF.h
436 0x4602 0x3303 HURT_UartReadSizeMissmatch HF_ExecutionFinished No description 2 3 HAL_UART HAS_ACTIONS_IF fsfw/src/fsfw_hal/linux/serial/SerialComIF.h fsfw/src/fsfw/action/HasActionsIF.h
437 0x4603 0x3304 HURT_UartRxBufferTooSmall HF_InvalidActionId No description 3 4 HAL_UART HAS_ACTIONS_IF fsfw/src/fsfw_hal/linux/serial/SerialComIF.h fsfw/src/fsfw/action/HasActionsIF.h
438 0x4400 0x1000 UXOS_ExecutionFinished TIM_UnsupportedTimeFormat Execution of the current command has finished 0 LINUX_OSAL CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw_hal/linux/CommandExecutor.h fsfw/src/fsfw/timemanager/CCSDSTime.h
439 0x4401 0x1001 UXOS_CommandPending TIM_NotEnoughInformationForTargetFormat 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 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw_hal/linux/CommandExecutor.h fsfw/src/fsfw/timemanager/CCSDSTime.h
440 0x4402 0x1002 UXOS_BytesRead TIM_LengthMismatch Some bytes have been read from the executing process 2 LINUX_OSAL CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw_hal/linux/CommandExecutor.h fsfw/src/fsfw/timemanager/CCSDSTime.h
441 0x1003 TIM_InvalidTimeFormat 3 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
442 0x1004 TIM_InvalidDayOfYear 4 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
443 0x1005 TIM_TimeDoesNotFitFormat 5 CCSDS_TIME_HELPER_CLASS fsfw/src/fsfw/timemanager/CCSDSTime.h
444 0x3701 TSI_BadTimestamp 1 TIME_STAMPER_IF fsfw/src/fsfw/timemanager/TimeStampIF.h
445 0x3c00 LPIF_PoolEntryNotFound 0 LOCAL_POOL_OWNER_IF fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h
446 0x3c01 LPIF_PoolEntryTypeConflict 1 LOCAL_POOL_OWNER_IF fsfw/src/fsfw/datapoollocal/localPoolDefinitions.h
447 0x3e00 HKM_QueueOrDestinationInvalid 0 HOUSEKEEPING_MANAGER fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
448 0x3e01 HKM_WrongHkPacketType 1 HOUSEKEEPING_MANAGER fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
449 0x3e02 HKM_ReportingStatusUnchanged 2 HOUSEKEEPING_MANAGER fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
450 0x3e03 HKM_PeriodicHelperInvalid 3 HOUSEKEEPING_MANAGER fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
451 0x3e04 HKM_PoolobjectNotFound 4 HOUSEKEEPING_MANAGER fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
452 0x3e05 HKM_DatasetNotFound 5 HOUSEKEEPING_MANAGER fsfw/src/fsfw/datapoollocal/LocalDataPoolManager.h
453 0x2901 TC_InvalidTargetState 1 THERMAL_COMPONENT_IF fsfw/src/fsfw/thermal/ThermalComponentIF.h
454 0x29f1 TC_AboveOperationalLimit 241 THERMAL_COMPONENT_IF fsfw/src/fsfw/thermal/ThermalComponentIF.h
455 0x29f2 TC_BelowOperationalLimit 242 THERMAL_COMPONENT_IF fsfw/src/fsfw/thermal/ThermalComponentIF.h
456 0x2001 CSB_ExecutionComplete 1 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
457 0x2002 CSB_NoStepMessage 2 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
458 0x2003 CSB_ObjectBusy 3 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
459 0x2004 CSB_Busy 4 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
460 0x2005 CSB_InvalidTc 5 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
461 0x2006 CSB_InvalidObject 6 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
462 0x2007 CSB_InvalidReply 7 COMMAND_SERVICE_BASE fsfw/src/fsfw/tmtcservices/CommandingServiceBase.h
463 0x4c00 SPPA_NoPacketFound 0 SPACE_PACKET_PARSER fsfw/src/fsfw/tmtcservices/SpacePacketParser.h
464 0x4c01 SPPA_SplitPacket 1 SPACE_PACKET_PARSER fsfw/src/fsfw/tmtcservices/SpacePacketParser.h
465 0x1d01 ATC_ActivityStarted 1 ACCEPTS_TELECOMMANDS_IF fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h
466 0x1d02 ATC_InvalidSubservice 2 ACCEPTS_TELECOMMANDS_IF fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h
467 0x1d03 ATC_IllegalApplicationData 3 ACCEPTS_TELECOMMANDS_IF fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h
468 0x1d04 ATC_SendTmFailed 4 ACCEPTS_TELECOMMANDS_IF fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h
469 0x1d05 ATC_Timeout 5 ACCEPTS_TELECOMMANDS_IF fsfw/src/fsfw/tmtcservices/AcceptsTelecommandsIF.h
470 0x7000 SCBU_KeyNotFound 0 SCRATCH_BUFFER bsp_q7s/memory/scratchApi.h
471 0x4403 0x64a0 UXOS_CommandError FSHLP_SdNotMounted Command execution failed SD card specified with path string not mounted 3 160 LINUX_OSAL FILE_SYSTEM_HELPER fsfw/src/fsfw_hal/linux/CommandExecutor.h bsp_q7s/fs/FilesystemHelper.h
472 0x4404 0x64a1 UXOS_NoCommandLoadedOrPending FSHLP_FileNotExists Specified file does not exist on filesystem 4 161 LINUX_OSAL FILE_SYSTEM_HELPER fsfw/src/fsfw_hal/linux/CommandExecutor.h bsp_q7s/fs/FilesystemHelper.h
473 0x4406 0x6f00 UXOS_PcloseCallError SDMA_OpOngoing No description 6 0 LINUX_OSAL SD_CARD_MANAGER fsfw/src/fsfw_hal/linux/CommandExecutor.h bsp_q7s/fs/SdCardManager.h
480 0x6f0b 0x6f0d SDMA_StatusFileFormatInvalid SDMA_UnmountError No description 11 13 SD_CARD_MANAGER bsp_q7s/fs/SdCardManager.h
481 0x6f0c 0x6f0e SDMA_MountError SDMA_SystemCallError No description 12 14 SD_CARD_MANAGER bsp_q7s/fs/SdCardManager.h
482 0x6f0d 0x6f0f SDMA_UnmountError SDMA_PopenCallError No description 13 15 SD_CARD_MANAGER bsp_q7s/fs/SdCardManager.h
483 0x6f0e 0x65a0 SDMA_SystemCallError PLMPHLP_FileClosedAccidentally No description File accidentally close 14 160 SD_CARD_MANAGER PLOC_MPSOC_HELPER bsp_q7s/fs/SdCardManager.h linux/devices/ploc/PlocMPSoCHelper.h
484 0x5ea0 PLMEMDUMP_MramAddressTooHigh The capacity of the MRAM amounts to 512 kB. Thus the maximum address must not be higher than 0x7d000. 160 PLOC_MEMORY_DUMPER linux/devices/ploc/PlocMemoryDumper.h
485 0x5ea1 PLMEMDUMP_MramInvalidAddressCombination The specified end address is lower than the start address 161 PLOC_MEMORY_DUMPER linux/devices/ploc/PlocMemoryDumper.h
486 0x6f0f 0x57a0 SDMA_PopenCallError PLSPVhLP_FileClosedAccidentally No description File accidentally close 15 160 SD_CARD_MANAGER PLOC_SUPV_HELPER bsp_q7s/fs/SdCardManager.h linux/devices/ploc/PlocSupvUartMan.h
487 0x64a0 0x57a1 FSHLP_SdNotMounted PLSPVhLP_ProcessTerminated SD card specified with path string not mounted Process has been terminated by command 160 161 FILE_SYSTEM_HELPER PLOC_SUPV_HELPER bsp_q7s/fs/FilesystemHelper.h linux/devices/ploc/PlocSupvUartMan.h
488 0x64a1 0x57a2 FSHLP_FileNotExists PLSPVhLP_PathNotExists Specified file does not exist on filesystem Received command with invalid pathname 161 162 FILE_SYSTEM_HELPER PLOC_SUPV_HELPER bsp_q7s/fs/FilesystemHelper.h linux/devices/ploc/PlocSupvUartMan.h
493 0x53a1 0x5703 STRH_PingFailed PLSPVhLP_PossiblePacketLossConsecutiveStart Ping command failed 161 3 STR_HANDLER PLOC_SUPV_HELPER linux/devices/startracker/StarTrackerHandler.h linux/devices/ploc/PlocSupvUartMan.h
494 0x53a2 0x5704 STRH_VersionReqFailed PLSPVhLP_PossiblePacketLossConsecutiveEnd Status in version reply signals error 162 4 STR_HANDLER PLOC_SUPV_HELPER linux/devices/startracker/StarTrackerHandler.h linux/devices/ploc/PlocSupvUartMan.h
495 0x53a3 0x5705 STRH_InterfaceReqFailed PLSPVhLP_HdlcError Status in interface reply signals error 163 5 STR_HANDLER PLOC_SUPV_HELPER linux/devices/startracker/StarTrackerHandler.h linux/devices/ploc/PlocSupvUartMan.h
496 0x53a4 0x67a0 STRH_PowerReqFailed MPSOCRTVIF_CrcFailure Status in power reply signals error Space Packet received from PLOC has invalid CRC 164 160 STR_HANDLER MPSOC_RETURN_VALUES_IF linux/devices/startracker/StarTrackerHandler.h linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
497 0x53a5 0x67a1 STRH_SetParamFailed MPSOCRTVIF_ReceivedAckFailure Status of reply to parameter set command signals error Received ACK failure reply from PLOC 165 161 STR_HANDLER MPSOC_RETURN_VALUES_IF linux/devices/startracker/StarTrackerHandler.h linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
498 0x53a6 0x67a2 STRH_ActionFailed MPSOCRTVIF_ReceivedExeFailure Status of reply to action command signals error Received execution failure reply from PLOC 166 162 STR_HANDLER MPSOC_RETURN_VALUES_IF linux/devices/startracker/StarTrackerHandler.h linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
499 0x53a7 0x67a3 STRH_FilePathTooLong MPSOCRTVIF_InvalidApid Received invalid path string. Exceeds allowed length Received space packet with invalid APID from PLOC 167 163 STR_HANDLER MPSOC_RETURN_VALUES_IF linux/devices/startracker/StarTrackerHandler.h linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
500 0x53a8 0x67a4 STRH_FilenameTooLong MPSOCRTVIF_InvalidLength Name of file received with command is too long Received command with invalid length 168 164 STR_HANDLER MPSOC_RETURN_VALUES_IF linux/devices/startracker/StarTrackerHandler.h linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
501 0x53a9 0x67a5 STRH_InvalidProgram MPSOCRTVIF_FilenameTooLong Received version reply with invalid program ID Filename of file in OBC filesystem is too long 169 165 STR_HANDLER MPSOC_RETURN_VALUES_IF linux/devices/startracker/StarTrackerHandler.h linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
502 0x53aa 0x67a6 STRH_ReplyError MPSOCRTVIF_MpsocHelperExecuting Status field reply signals error MPSoC helper is currently executing a command 170 166 STR_HANDLER MPSOC_RETURN_VALUES_IF linux/devices/startracker/StarTrackerHandler.h linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
503 0x53ab 0x67a7 STRH_CommandTooShort MPSOCRTVIF_MpsocFilenameTooLong Received command which is too short (some data is missing for proper execution) Filename of MPSoC file is to long (max. 256 bytes) 171 167 STR_HANDLER MPSOC_RETURN_VALUES_IF linux/devices/startracker/StarTrackerHandler.h linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
504 0x53ac 0x67a8 STRH_InvalidLength MPSOCRTVIF_InvalidParameter Received command with invalid length (too few or too many parameters) Command has invalid parameter 172 168 STR_HANDLER MPSOC_RETURN_VALUES_IF linux/devices/startracker/StarTrackerHandler.h linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
505 0x53ad 0x67a9 STRH_RegionMismatch MPSOCRTVIF_NameTooLong Region mismatch between send and received data Received command has file string with invalid length 173 169 STR_HANDLER MPSOC_RETURN_VALUES_IF linux/devices/startracker/StarTrackerHandler.h linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x53ae STRH_AddressMismatch Address mismatch between send and received data 174 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
0x53af STRH_LengthMismatch Length field mismatch between send and received data 175 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
0x53b0 STRH_FileNotExists Specified file does not exist 176 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
0x53b1 STRH_InvalidType Download blob pixel command has invalid type field 177 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
0x53b2 STRH_InvalidId Received FPGA action command with invalid ID 178 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
0x53b3 STRH_ReplyTooShort Received reply is too short 179 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
0x53b4 STRH_CrcFailure Received reply with invalid CRC 180 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
0x53b5 STRH_StrHelperExecuting Star tracker handler currently executing a command and using the communication interface 181 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
0x53b6 STRH_StartrackerAlreadyBooted Star tracker is already in firmware mode 182 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
0x53b7 STRH_StartrackerRunningFirmware Star tracker is in firmware mode but must be in bootloader mode to execute this command 183 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
0x53b8 STRH_StartrackerRunningBootloader Star tracker is in bootloader mode but must be in firmware mode to execute this command 184 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
0x5ca0 STRHLP_SdNotMounted SD card specified in path string not mounted 160 STR_HELPER linux/devices/startracker/StrHelper.h
0x5ca1 STRHLP_FileNotExists Specified file does not exist on filesystem 161 STR_HELPER linux/devices/startracker/StrHelper.h
0x5ca2 STRHLP_PathNotExists Specified path does not exist 162 STR_HELPER linux/devices/startracker/StrHelper.h
0x5ca3 STRHLP_FileCreationFailed Failed to create download image or read flash file 163 STR_HELPER linux/devices/startracker/StrHelper.h
0x5ca4 STRHLP_RegionMismatch Region in flash write/read reply does not match expected region 164 STR_HELPER linux/devices/startracker/StrHelper.h
0x5ca5 STRHLP_AddressMismatch Address in flash write/read reply does not match expected address 165 STR_HELPER linux/devices/startracker/StrHelper.h
0x5ca6 STRHLP_LengthMismatch Length in flash write/read reply does not match expected length 166 STR_HELPER linux/devices/startracker/StrHelper.h
0x5ca7 STRHLP_StatusError Status field in reply signals error 167 STR_HELPER linux/devices/startracker/StrHelper.h
0x5ca8 STRHLP_InvalidTypeId Reply has invalid type ID (should be of action reply type) 168 STR_HELPER linux/devices/startracker/StrHelper.h
0x54e0 DWLPWRON_InvalidMode Received command has invalid JESD mode (valid modes are 0 - 5) 224 DWLPWRON_CMD linux/devices/devicedefinitions/PlocMPSoCDefinitions.h
0x54e1 DWLPWRON_InvalidLaneRate Received command has invalid lane rate (valid lane rate are 0 - 9) 225 DWLPWRON_CMD linux/devices/devicedefinitions/PlocMPSoCDefinitions.h
0x68a0 SPVRTVIF_CrcFailure Space Packet received from PLOC supervisor has invalid CRC 160 SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
0x68a1 SPVRTVIF_InvalidServiceId No description 161 SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
0x68a2 SPVRTVIF_ReceivedAckFailure Received ACK failure reply from PLOC supervisor 162 SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
0x68a3 SPVRTVIF_ReceivedExeFailure Received execution failure reply from PLOC supervisor 163 SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
0x68a4 SPVRTVIF_InvalidApid Received space packet with invalid APID from PLOC supervisor 164 SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
0x68a5 SPVRTVIF_GetTimeFailure Failed to read current system time 165 SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
0x68a6 SPVRTVIF_InvalidWatchdog Received command with invalid watchdog parameter. Valid watchdogs are 0 for PS, 1 for PL and 2 for INT 166 SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
0x68a7 SPVRTVIF_InvalidWatchdogTimeout Received watchdog timeout config command with invalid timeout. Valid timeouts must be in the range between 1000 and 360000 ms. 167 SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
506 0x68a8 0x68a0 SPVRTVIF_InvalidLatchupId SPVRTVIF_CrcFailure Received latchup config command with invalid latchup ID Space Packet received from PLOC supervisor has invalid CRC 168 160 SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
507 0x68a9 0x68a1 SPVRTVIF_SweepPeriodTooSmall SPVRTVIF_InvalidServiceId Received set adc sweep period command with invalid sweep period. Must be larger than 21. 169 161 SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
508 0x68aa 0x68a2 SPVRTVIF_InvalidTestParam SPVRTVIF_ReceivedAckFailure Receive auto EM test command with invalid test param. Valid params are 1 and 2. Received ACK failure reply from PLOC supervisor 170 162 SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
527 0x67a5 0x68b5 MPSOCRTVIF_FilenameTooLong SPVRTVIF_SupvHelperExecuting Filename of file in OBC filesystem is too long Supervisor helper task ist currently executing a command (wait until helper tas has finished or interrupt by sending the terminate command) 165 181 MPSOC_RETURN_VALUES_IF SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/MPSoCReturnValuesIF.h linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
528 0x67a6 0x68c0 MPSOCRTVIF_MpsocHelperExecuting SPVRTVIF_BufTooSmall MPSoC helper is currently executing a command 166 192 MPSOC_RETURN_VALUES_IF SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/MPSoCReturnValuesIF.h linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
529 0x67a7 0x68c1 MPSOCRTVIF_MpsocFilenameTooLong SPVRTVIF_NoReplyTimeout Filename of MPSoC file is to long (max. 256 bytes) 167 193 MPSOC_RETURN_VALUES_IF SUPV_RETURN_VALUES_IF linux/devices/devicedefinitions/MPSoCReturnValuesIF.h linux/devices/devicedefinitions/PlocSupervisorDefinitions.h
0x67a8 MPSOCRTVIF_InvalidParameter Command has invalid parameter 168 MPSOC_RETURN_VALUES_IF linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x67a9 MPSOCRTVIF_NameTooLong Received command has file string with invalid length 169 MPSOC_RETURN_VALUES_IF linux/devices/devicedefinitions/MPSoCReturnValuesIF.h
0x65a0 PLMPHLP_FileClosedAccidentally File accidentally close 160 PLOC_MPSOC_HELPER linux/devices/ploc/PlocMPSoCHelper.h
0x57a0 PLSPVhLP_FileClosedAccidentally File accidentally close 160 PLOC_SUPV_HELPER linux/devices/ploc/PlocSupvUartMan.h
0x57a1 PLSPVhLP_ProcessTerminated Process has been terminated by command 161 PLOC_SUPV_HELPER linux/devices/ploc/PlocSupvUartMan.h
0x57a2 PLSPVhLP_PathNotExists Received command with invalid pathname 162 PLOC_SUPV_HELPER linux/devices/ploc/PlocSupvUartMan.h
0x57a3 PLSPVhLP_EventBufferReplyInvalidApid Expected event buffer TM but received space packet with other APID 163 PLOC_SUPV_HELPER linux/devices/ploc/PlocSupvUartMan.h
0x5700 PLSPVhLP_RequestDone No description 0 PLOC_SUPV_HELPER linux/devices/ploc/PlocSupvUartMan.h
0x5701 PLSPVhLP_NoPacketFound No description 1 PLOC_SUPV_HELPER linux/devices/ploc/PlocSupvUartMan.h
0x5702 PLSPVhLP_DecodeBufTooSmall No description 2 PLOC_SUPV_HELPER linux/devices/ploc/PlocSupvUartMan.h
530 0x5703 0x54e0 PLSPVhLP_PossiblePacketLossConsecutiveStart DWLPWRON_InvalidMode No description Received command has invalid JESD mode (valid modes are 0 - 5) 3 224 PLOC_SUPV_HELPER DWLPWRON_CMD linux/devices/ploc/PlocSupvUartMan.h linux/devices/devicedefinitions/PlocMPSoCDefinitions.h
531 0x5704 0x54e1 PLSPVhLP_PossiblePacketLossConsecutiveEnd DWLPWRON_InvalidLaneRate No description Received command has invalid lane rate (valid lane rate are 0 - 9) 4 225 PLOC_SUPV_HELPER DWLPWRON_CMD linux/devices/ploc/PlocSupvUartMan.h linux/devices/devicedefinitions/PlocMPSoCDefinitions.h
532 0x5705 0x6201 PLSPVhLP_HdlcError JSONBASE_JsonFileNotExists No description Specified json file does not exist 5 1 PLOC_SUPV_HELPER ARCSEC_JSON_BASE linux/devices/ploc/PlocSupvUartMan.h linux/devices/startracker/ArcsecJsonParamBase.h
533 0x5ea0 0x6202 PLMEMDUMP_MramAddressTooHigh JSONBASE_SetNotExists The capacity of the MRAM amounts to 512 kB. Thus the maximum address must not be higher than 0x7d000. Requested set does not exist in json file 160 2 PLOC_MEMORY_DUMPER ARCSEC_JSON_BASE linux/devices/ploc/PlocMemoryDumper.h linux/devices/startracker/ArcsecJsonParamBase.h
534 0x6203 JSONBASE_ParamNotExists Requested parameter does not exist in json file 3 ARCSEC_JSON_BASE linux/devices/startracker/ArcsecJsonParamBase.h
535 0x53a0 STRH_TemperatureReqFailed Status in temperature reply signals error 160 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
536 0x53a1 STRH_PingFailed Ping command failed 161 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
537 0x53a2 STRH_VersionReqFailed Status in version reply signals error 162 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
538 0x5ca0 STRHLP_SdNotMounted SD card specified in path string not mounted 160 STR_HELPER linux/devices/startracker/StrHelper.h
539 0x5ca1 STRHLP_FileNotExists Specified file does not exist on filesystem 161 STR_HELPER linux/devices/startracker/StrHelper.h
540 0x5ca2 STRHLP_PathNotExists Specified path does not exist 162 STR_HELPER linux/devices/startracker/StrHelper.h
541 0x5ca3 STRHLP_FileCreationFailed Failed to create download image or read flash file 163 STR_HELPER linux/devices/startracker/StrHelper.h
542 0x5ca4 STRHLP_RegionMismatch Region in flash write/read reply does not match expected region 164 STR_HELPER linux/devices/startracker/StrHelper.h
543 0x5ca5 STRHLP_AddressMismatch Address in flash write/read reply does not match expected address 165 STR_HELPER linux/devices/startracker/StrHelper.h
544 0x5ca6 STRHLP_LengthMismatch Length in flash write/read reply does not match expected length 166 STR_HELPER linux/devices/startracker/StrHelper.h
545 0x5ca7 STRHLP_StatusError Status field in reply signals error 167 STR_HELPER linux/devices/startracker/StrHelper.h
546 0x5ca8 STRHLP_InvalidTypeId Reply has invalid type ID (should be of action reply type) 168 STR_HELPER linux/devices/startracker/StrHelper.h
547 0x53a3 STRH_InterfaceReqFailed Status in interface reply signals error 163 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
548 0x53a4 STRH_PowerReqFailed Status in power reply signals error 164 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
549 0x53a5 STRH_SetParamFailed Status of reply to parameter set command signals error 165 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
550 0x53a6 STRH_ActionFailed Status of reply to action command signals error 166 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
551 0x53a7 STRH_FilePathTooLong Received invalid path string. Exceeds allowed length 167 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
552 0x53a8 STRH_FilenameTooLong Name of file received with command is too long 168 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
553 0x53a9 STRH_InvalidProgram Received version reply with invalid program ID 169 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
554 0x53aa STRH_ReplyError Status field reply signals error 170 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
555 0x53ab STRH_CommandTooShort Received command which is too short (some data is missing for proper execution) 171 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
556 0x53ac STRH_InvalidLength Received command with invalid length (too few or too many parameters) 172 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
557 0x53ad STRH_RegionMismatch Region mismatch between send and received data 173 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
558 0x53ae STRH_AddressMismatch Address mismatch between send and received data 174 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
559 0x53af STRH_LengthMismatch Length field mismatch between send and received data 175 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
560 0x53b0 STRH_FileNotExists Specified file does not exist 176 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
561 0x53b1 STRH_InvalidType Download blob pixel command has invalid type field 177 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
562 0x53b2 STRH_InvalidId Received FPGA action command with invalid ID 178 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
563 0x53b3 STRH_ReplyTooShort Received reply is too short 179 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
564 0x53b4 STRH_CrcFailure Received reply with invalid CRC 180 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
565 0x53b5 STRH_StrHelperExecuting Star tracker handler currently executing a command and using the communication interface 181 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
566 0x53b6 STRH_StartrackerAlreadyBooted Star tracker is already in firmware mode 182 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
567 0x53b7 STRH_StartrackerRunningFirmware Star tracker is in firmware mode but must be in bootloader mode to execute this command 183 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
568 0x53b8 STRH_StartrackerRunningBootloader Star tracker is in bootloader mode but must be in firmware mode to execute this command 184 STR_HANDLER linux/devices/startracker/StarTrackerHandler.h
569 0x5302 STRH_InvalidCrc 2 STR_HANDLER linux/devices/ScexHelper.h
570 0x5ea1 0x5aa0 PLMEMDUMP_MramInvalidAddressCombination PTME_UnknownVcId The specified end address is lower than the start address 161 160 PLOC_MEMORY_DUMPER PTME linux/devices/ploc/PlocMemoryDumper.h linux/ipcore/Ptme.h
571 0x5e02 0x5fa0 PLMEMDUMP_InvalidCrc PDEC_AbandonedCltu No description 2 160 PLOC_MEMORY_DUMPER PDEC_HANDLER linux/devices/ScexHelper.h linux/ipcore/PdecHandler.h
572 0x5e00 0x5fa1 PLMEMDUMP_NoReplyAvailable PDEC_FrameDirty No description 0 161 PLOC_MEMORY_DUMPER PDEC_HANDLER linux/devices/ImtqPollingTask.h linux/ipcore/PdecHandler.h
587 0x5fa9 0x61a1 PDEC_InvalidScIdRetval RS_BadBitRate No description Bad bitrate has been commanded (e.g. 0) 169 161 PDEC_HANDLER RATE_SETTER linux/ipcore/PdecHandler.h linux/ipcore/PtmeConfig.h
588 0x5faa 0x61a2 PDEC_InvalidVcIdMsbRetval RS_ClkInversionFailed No description Failed to invert clock and thus change the time the data is updated with respect to the tx clock 170 162 PDEC_HANDLER RATE_SETTER linux/ipcore/PdecHandler.h linux/ipcore/PtmeConfig.h
589 0x5fab 0x61a3 PDEC_InvalidVcIdLsbRetval RS_TxManipulatorConfigFailed No description Failed to change configuration bit of tx clock manipulator 171 163 PDEC_HANDLER RATE_SETTER linux/ipcore/PdecHandler.h linux/ipcore/PtmeConfig.h
590 0x59a0 IPCI_PapbBusy 160 CCSDS_IP_CORE_BRIDGE linux/ipcore/PapbVcInterface.h

View File

@ -1,7 +1,7 @@
/** /**
* @brief Auto-generated event translation file. Contains 256 translations. * @brief Auto-generated event translation file. Contains 256 translations.
* @details * @details
* Generated on: 2023-02-13 10:07:30 * Generated on: 2023-02-17 02:12:04
*/ */
#include "translateEvents.h" #include "translateEvents.h"

View File

@ -2,7 +2,7 @@
* @brief Auto-generated object translation file. * @brief Auto-generated object translation file.
* @details * @details
* Contains 152 translations. * Contains 152 translations.
* Generated on: 2023-02-13 10:07:30 * Generated on: 2023-02-17 02:12:04
*/ */
#include "translateObjects.h" #include "translateObjects.h"
@ -84,7 +84,7 @@ const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF";
const char *GPIO_IF_STRING = "GPIO_IF"; const char *GPIO_IF_STRING = "GPIO_IF";
const char *SCEX_UART_READER_STRING = "SCEX_UART_READER"; const char *SCEX_UART_READER_STRING = "SCEX_UART_READER";
const char *SPI_MAIN_COM_IF_STRING = "SPI_MAIN_COM_IF"; const char *SPI_MAIN_COM_IF_STRING = "SPI_MAIN_COM_IF";
const char *SPI_RW_COM_IF_STRING = "SPI_RW_COM_IF"; const char *RW_POLLING_TASK_STRING = "RW_POLLING_TASK";
const char *SPI_RTD_COM_IF_STRING = "SPI_RTD_COM_IF"; const char *SPI_RTD_COM_IF_STRING = "SPI_RTD_COM_IF";
const char *UART_COM_IF_STRING = "UART_COM_IF"; const char *UART_COM_IF_STRING = "UART_COM_IF";
const char *I2C_COM_IF_STRING = "I2C_COM_IF"; const char *I2C_COM_IF_STRING = "I2C_COM_IF";
@ -318,7 +318,7 @@ const char *translateObject(object_id_t object) {
case 0x49020004: case 0x49020004:
return SPI_MAIN_COM_IF_STRING; return SPI_MAIN_COM_IF_STRING;
case 0x49020005: case 0x49020005:
return SPI_RW_COM_IF_STRING; return RW_POLLING_TASK_STRING;
case 0x49020006: case 0x49020006:
return SPI_RTD_COM_IF_STRING; return SPI_RTD_COM_IF_STRING;
case 0x49030003: case 0x49030003:

View File

@ -4,7 +4,7 @@ endif()
target_sources( target_sources(
${OBSW_NAME} PRIVATE Max31865RtdLowlevelHandler.cpp ScexUartReader.cpp ${OBSW_NAME} PRIVATE Max31865RtdLowlevelHandler.cpp ScexUartReader.cpp
ScexDleParser.cpp ScexHelper.cpp) ScexDleParser.cpp ScexHelper.cpp RwPollingTask.cpp)
add_subdirectory(ploc) add_subdirectory(ploc)

View File

@ -0,0 +1,532 @@
#include "RwPollingTask.h"
#include <fcntl.h>
#include <fsfw/globalfunctions/CRC.h>
#include <fsfw/tasks/SemaphoreFactory.h>
#include <fsfw/tasks/TaskFactory.h>
#include <fsfw/timemanager/Stopwatch.h>
#include <fsfw_hal/common/spi/spiCommon.h>
#include <fsfw_hal/linux/utility.h>
#include <sys/ioctl.h>
#include <unistd.h>
#include "devConf.h"
#include "mission/devices/devicedefinitions/rwHelpers.h"
RwPollingTask::RwPollingTask(object_id_t objectId, const char* spiDev, GpioIF& gpioIF)
: SystemObject(objectId), spiDev(spiDev), gpioIF(gpioIF) {
semaphore = SemaphoreFactory::instance()->createBinarySemaphore();
semaphore->acquire();
ipcLock = MutexFactory::instance()->createMutex();
spiLock = MutexFactory::instance()->createMutex();
}
ReturnValue_t RwPollingTask::performOperation(uint8_t operationCode) {
for (unsigned i = 0; i < 4; i++) {
if (rwCookies[i] == nullptr) {
sif::error << "Invalid RW cookie at index" << i << std::endl;
return returnvalue::FAILED;
}
}
while (true) {
ipcLock->lockMutex();
state = InternalState::IDLE;
ipcLock->unlockMutex();
semaphore->acquire();
// This loop takes 50 ms on a debug build.
// Stopwatch watch;
TaskFactory::delayTask(5);
int fd = 0;
for (auto& skip : skipCommandingForRw) {
skip = false;
}
setAllReadFlagsFalse();
ReturnValue_t result = openSpi(O_RDWR, fd);
if (result != returnvalue::OK) {
continue;
}
for (unsigned idx = 0; idx < rwCookies.size(); idx++) {
if (rwCookies[idx]->specialRequest == rws::SpecialRwRequest::RESET_MCU) {
prepareSimpleCommand(rws::RESET_MCU);
// No point in commanding that specific RW for the cycle.
skipCommandingForRw[idx] = true;
writeOneRwCmd(idx, fd);
} else if (rwCookies[idx]->setSpeed) {
prepareSetSpeedCmd(idx);
if (writeOneRwCmd(idx, fd) != returnvalue::OK) {
continue;
}
}
}
closeSpi(fd);
if (readAllRws(rws::SET_SPEED) != returnvalue::OK) {
continue;
}
prepareSimpleCommand(rws::GET_LAST_RESET_STATUS);
if (writeAndReadAllRws(rws::GET_LAST_RESET_STATUS) != returnvalue::OK) {
continue;
}
prepareSimpleCommand(rws::GET_RW_STATUS);
if (writeAndReadAllRws(rws::GET_RW_STATUS) != returnvalue::OK) {
continue;
}
prepareSimpleCommand(rws::GET_TEMPERATURE);
if (writeAndReadAllRws(rws::GET_TEMPERATURE) != returnvalue::OK) {
continue;
}
prepareSimpleCommand(rws::CLEAR_LAST_RESET_STATUS);
if (writeAndReadAllRws(rws::CLEAR_LAST_RESET_STATUS) != returnvalue::OK) {
continue;
}
handleSpecialRequests();
}
return returnvalue::OK;
}
ReturnValue_t RwPollingTask::initialize() { return returnvalue::OK; }
ReturnValue_t RwPollingTask::initializeInterface(CookieIF* cookie) {
// We don't need to set the speed because a SPI core is used, but the mode has to be set once
// correctly for all RWs
if (not modeAndSpeedWasSet) {
int fd = open(spiDev, O_RDWR);
if (fd < 0) {
sif::error << "could not open RW SPI bus" << std::endl;
return returnvalue::FAILED;
}
spi::SpiModes mode = spi::RW_MODE;
int retval = ioctl(fd, SPI_IOC_WR_MODE, reinterpret_cast<uint8_t*>(&mode));
if (retval != 0) {
utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Setting SPI mode failed");
}
retval = ioctl(fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi::RW_SPEED);
if (retval != 0) {
utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Setting SPI speed failed");
}
close(fd);
modeAndSpeedWasSet = true;
}
auto* rwCookie = dynamic_cast<RwCookie*>(cookie);
if (rwCookie == nullptr) {
sif::error << "RwPollingTask::initializeInterface: Wrong cookie" << std::endl;
return returnvalue::FAILED;
}
rwCookies[rwCookie->rwIdx] = rwCookie;
return returnvalue::OK;
}
ReturnValue_t RwPollingTask::sendMessage(CookieIF* cookie, const uint8_t* sendData,
size_t sendLen) {
if (sendData == nullptr or sendLen < 8) {
return DeviceHandlerIF::INVALID_DATA;
}
int32_t speed = 0;
uint16_t rampTime = 0;
const uint8_t* currentBuf = sendData;
bool setSpeed = currentBuf[0];
currentBuf += 1;
sendLen -= 1;
SerializeAdapter::deSerialize(&speed, &currentBuf, &sendLen, SerializeIF::Endianness::MACHINE);
SerializeAdapter::deSerialize(&rampTime, &currentBuf, &sendLen, SerializeIF::Endianness::MACHINE);
rws::SpecialRwRequest specialRequest = rws::SpecialRwRequest::REQUEST_NONE;
if (sendLen == 8 and sendData[7] < static_cast<uint8_t>(rws::SpecialRwRequest::NUM_REQUESTS)) {
specialRequest = static_cast<rws::SpecialRwRequest>(sendData[7]);
}
RwCookie* rwCookie = dynamic_cast<RwCookie*>(cookie);
if (rwCookie == nullptr) {
return returnvalue::FAILED;
}
{
MutexGuard mg(ipcLock);
rwCookie->setSpeed = setSpeed;
rwCookie->currentRwSpeed = speed;
rwCookie->currentRampTime = rampTime;
rwCookie->specialRequest = specialRequest;
if (state == InternalState::IDLE) {
state = InternalState::BUSY;
semaphore->release();
}
}
return returnvalue::OK;
}
ReturnValue_t RwPollingTask::getSendSuccess(CookieIF* cookie) { return returnvalue::OK; }
ReturnValue_t RwPollingTask::requestReceiveMessage(CookieIF* cookie, size_t requestLen) {
return returnvalue::OK;
}
ReturnValue_t RwPollingTask::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) {
RwCookie* rwCookie = dynamic_cast<RwCookie*>(cookie);
{
MutexGuard mg(ipcLock);
*buffer = rwCookie->replyBuf.data();
*size = rwCookie->replyBuf.size();
}
return returnvalue::OK;
}
ReturnValue_t RwPollingTask::writeAndReadAllRws(DeviceCommandId_t id) {
// Stopwatch watch;
ReturnValue_t result = returnvalue::OK;
int fd = 0;
result = openSpi(O_RDWR, fd);
if (result != returnvalue::OK) {
return result;
}
for (unsigned idx = 0; idx < rwCookies.size(); idx++) {
if (skipCommandingForRw[idx]) {
continue;
}
ReturnValue_t result = sendOneMessage(fd, *rwCookies[idx]);
if (result != returnvalue::OK) {
closeSpi(fd);
return returnvalue::FAILED;
}
}
closeSpi(fd);
return readAllRws(id);
}
ReturnValue_t RwPollingTask::openSpi(int flags, int& fd) {
fd = open(spiDev, flags);
if (fd < 0) {
sif::error << "RwPollingTask::openSpi: Failed to open device file" << std::endl;
return SpiComIF::OPENING_FILE_FAILED;
}
return returnvalue::OK;
}
ReturnValue_t RwPollingTask::readNextReply(RwCookie& rwCookie, uint8_t* replyBuf,
size_t maxReplyLen) {
ReturnValue_t result = returnvalue::OK;
int fd = 0;
gpioId_t gpioId = rwCookie.getChipSelectPin();
uint8_t byteRead = 0;
result = openSpi(O_RDWR, fd);
if (result != returnvalue::OK) {
return result;
}
pullCsLow(gpioId, gpioIF);
bool lastByteWasFrameMarker = false;
Countdown cd(3000);
size_t readIdx = 0;
while (true) {
lastByteWasFrameMarker = false;
if (read(fd, &byteRead, 1) != 1) {
sif::error << "RwPollingTask: Read failed. " << strerror(errno) << std::endl;
pullCsHigh(gpioId, gpioIF);
closeSpi(fd);
return rws::SPI_READ_FAILURE;
}
if (byteRead == rws::FRAME_DELIMITER) {
lastByteWasFrameMarker = true;
}
// Start of frame detected.
if (byteRead != rws::FRAME_DELIMITER and not lastByteWasFrameMarker) {
break;
}
if (readIdx % 100 == 0 && cd.hasTimedOut()) {
pullCsHigh(gpioId, gpioIF);
closeSpi(fd);
return rws::SPI_READ_FAILURE;
}
readIdx++;
}
#if FSFW_HAL_SPI_WIRETAPPING == 1
sif::info << "RW start marker detected" << std::endl;
#endif
size_t decodedFrameLen = 0;
while (decodedFrameLen < maxReplyLen) {
// First byte already read in
if (decodedFrameLen != 0) {
byteRead = 0;
if (read(fd, &byteRead, 1) != 1) {
sif::error << "RwPollingTask: Read failed" << std::endl;
result = rws::SPI_READ_FAILURE;
break;
}
}
if (byteRead == rws::FRAME_DELIMITER) {
// Reached end of frame
break;
} else if (byteRead == 0x7D) {
if (read(fd, &byteRead, 1) != 1) {
sif::error << "RwPollingTask: Read failed" << std::endl;
result = rws::SPI_READ_FAILURE;
break;
}
if (byteRead == 0x5E) {
*(replyBuf + decodedFrameLen) = 0x7E;
decodedFrameLen++;
continue;
} else if (byteRead == 0x5D) {
*(replyBuf + decodedFrameLen) = 0x7D;
decodedFrameLen++;
continue;
} else {
sif::error << "RwPollingTask: Invalid substitute" << std::endl;
result = rws::INVALID_SUBSTITUTE;
break;
}
} else {
*(replyBuf + decodedFrameLen) = byteRead;
decodedFrameLen++;
continue;
}
// Check end marker.
/**
* There might be the unlikely case that each byte in a get-telemetry reply has been
* replaced by its substitute. Then the next byte must correspond to the end sign 0x7E.
* Otherwise there might be something wrong.
*/
if (decodedFrameLen == maxReplyLen) {
if (read(fd, &byteRead, 1) != 1) {
sif::error << "rwSpiCallback::spiCallback: Failed to read last byte" << std::endl;
result = rws::SPI_READ_FAILURE;
break;
}
if (byteRead != rws::FRAME_DELIMITER) {
sif::error << "rwSpiCallback::spiCallback: Missing end sign "
<< static_cast<int>(rws::FRAME_DELIMITER) << std::endl;
decodedFrameLen--;
result = rws::MISSING_END_SIGN;
break;
}
}
result = returnvalue::OK;
}
pullCsHigh(gpioId, gpioIF);
closeSpi(fd);
return result;
}
ReturnValue_t RwPollingTask::writeOneRwCmd(uint8_t rwIdx, int fd) {
ReturnValue_t result = sendOneMessage(fd, *rwCookies[rwIdx]);
if (result != returnvalue::OK) {
return returnvalue::FAILED;
}
return returnvalue::OK;
}
ReturnValue_t RwPollingTask::readAllRws(DeviceCommandId_t id) {
// SPI dev will be opened in readNextReply on demand.
for (unsigned idx = 0; idx < rwCookies.size(); idx++) {
if (((id == rws::SET_SPEED) and !rwCookies[idx]->setSpeed) or skipCommandingForRw[idx]) {
continue;
}
uint8_t* replyBuf;
size_t maxReadLen = idAndIdxToReadBuffer(id, idx, &replyBuf);
ReturnValue_t result = readNextReply(*rwCookies[idx], replyBuf + 1, maxReadLen);
if (result == returnvalue::OK) {
// The first byte is always a flag which shows whether the value was read
// properly at least once.
replyBuf[0] = true;
}
}
// SPI is closed in readNextReply as well.
return returnvalue::OK;
}
size_t RwPollingTask::idAndIdxToReadBuffer(DeviceCommandId_t id, uint8_t rwIdx, uint8_t** ptr) {
uint8_t* rawStart = rwCookies[rwIdx]->replyBuf.data();
RwReplies replies(rawStart);
switch (id) {
case (rws::GET_RW_STATUS): {
*ptr = replies.rwStatusReply;
break;
}
case (rws::SET_SPEED): {
*ptr = replies.setSpeedReply;
break;
}
case (rws::CLEAR_LAST_RESET_STATUS): {
*ptr = replies.clearLastResetStatusReply;
break;
}
case (rws::GET_LAST_RESET_STATUS): {
*ptr = replies.getLastResetStatusReply;
break;
}
case (rws::GET_TEMPERATURE): {
*ptr = replies.readTemperatureReply;
break;
}
case (rws::GET_TM): {
*ptr = replies.hkDataReply;
break;
}
case (rws::INIT_RW_CONTROLLER): {
*ptr = replies.initRwControllerReply;
break;
}
default: {
sif::error << "no reply buffer for rw command " << id << std::endl;
*ptr = replies.dummyPointer;
return 0;
}
}
return rws::idToPacketLen(id);
}
void RwPollingTask::fillSpecialRequestArray() {
for (unsigned idx = 0; idx < rwCookies.size(); idx++) {
if (skipCommandingForRw[idx]) {
specialRequestIds[idx] = DeviceHandlerIF::NO_COMMAND_ID;
continue;
}
switch (rwCookies[idx]->specialRequest) {
case (rws::SpecialRwRequest::GET_TM): {
specialRequestIds[idx] = rws::GET_TM;
break;
}
case (rws::SpecialRwRequest::INIT_RW_CONTROLLER): {
specialRequestIds[idx] = rws::INIT_RW_CONTROLLER;
break;
}
default: {
specialRequestIds[idx] = DeviceHandlerIF::NO_COMMAND_ID;
}
}
}
}
void RwPollingTask::handleSpecialRequests() {
int fd = 0;
fillSpecialRequestArray();
ReturnValue_t result = openSpi(O_RDWR, fd);
if (result != returnvalue::OK) {
return;
}
for (unsigned idx = 0; idx < rwCookies.size(); idx++) {
if (specialRequestIds[idx] == DeviceHandlerIF::NO_COMMAND_ID) {
continue;
}
prepareSimpleCommand(specialRequestIds[idx]);
writeOneRwCmd(idx, fd);
}
closeSpi(fd);
usleep(rws::SPI_REPLY_DELAY);
for (unsigned idx = 0; idx < rwCookies.size(); idx++) {
if (specialRequestIds[idx] == DeviceHandlerIF::NO_COMMAND_ID) {
continue;
}
uint8_t* replyBuf;
size_t maxReadLen = idAndIdxToReadBuffer(specialRequestIds[idx], idx, &replyBuf);
readNextReply(*rwCookies[idx], replyBuf, maxReadLen);
}
}
void RwPollingTask::setAllReadFlagsFalse() {
for (auto& rwCookie : rwCookies) {
RwReplies replies(rwCookie->replyBuf.data());
replies.getLastResetStatusReply[0] = false;
replies.clearLastResetStatusReply[0] = false;
replies.hkDataReply[0] = false;
replies.readTemperatureReply[0] = false;
replies.rwStatusReply[0] = false;
replies.setSpeedReply[0] = false;
replies.initRwControllerReply[0] = false;
}
}
// This closes the SPI
void RwPollingTask::closeSpi(int fd) {
// This will perform the function to close the SPI
close(fd);
// The SPI is now closed.
}
ReturnValue_t RwPollingTask::sendOneMessage(int fd, RwCookie& rwCookie) {
gpioId_t gpioId = rwCookie.getChipSelectPin();
if (spiLock == nullptr) {
sif::debug << "rwSpiCallback::spiCallback: Mutex or GPIO interface invalid" << std::endl;
return returnvalue::FAILED;
}
// Add datalinklayer like specified in the datasheet.
size_t lenToSend = 0;
rws::encodeHdlc(writeBuffer.data(), writeLen, encodedBuffer.data(), lenToSend);
pullCsLow(gpioId, gpioIF);
if (write(fd, encodedBuffer.data(), lenToSend) != static_cast<ssize_t>(lenToSend)) {
sif::error << "rwSpiCallback::spiCallback: Write failed!" << std::endl;
pullCsHigh(gpioId, gpioIF);
return rws::SPI_WRITE_FAILURE;
}
pullCsHigh(gpioId, gpioIF);
return returnvalue::OK;
}
ReturnValue_t RwPollingTask::pullCsLow(gpioId_t gpioId, GpioIF& gpioIF) {
ReturnValue_t result = spiLock->lockMutex(TIMEOUT_TYPE, TIMEOUT_MS);
if (result != returnvalue::OK) {
sif::debug << "RwPollingTask::pullCsLow: Failed to lock mutex" << std::endl;
return result;
}
// Pull SPI CS low. For now, no support for active high given
if (gpioId != gpio::NO_GPIO) {
ReturnValue_t result = gpioIF.pullLow(gpioId);
if (result != returnvalue::OK) {
sif::error << "RwPollingTask::pullCsLow: Failed to pull chip select low" << std::endl;
return result;
}
}
return returnvalue::OK;
}
void RwPollingTask::pullCsHigh(gpioId_t gpioId, GpioIF& gpioIF) {
if (gpioId != gpio::NO_GPIO) {
if (gpioIF.pullHigh(gpioId) != returnvalue::OK) {
sif::error << "closeSpi: Failed to pull chip select high" << std::endl;
}
}
if (spiLock->unlockMutex() != returnvalue::OK) {
sif::error << "RwPollingTask::pullCsHigh: Failed to unlock mutex" << std::endl;
;
}
}
void RwPollingTask::prepareSimpleCommand(DeviceCommandId_t id) {
writeBuffer[0] = static_cast<uint8_t>(id);
uint16_t crc = CRC::crc16ccitt(writeBuffer.data(), 1, 0xFFFF);
writeBuffer[1] = static_cast<uint8_t>(crc & 0xFF);
writeBuffer[2] = static_cast<uint8_t>(crc >> 8 & 0xFF);
writeLen = 3;
}
ReturnValue_t RwPollingTask::prepareSetSpeedCmd(uint8_t rwIdx) {
writeBuffer[0] = static_cast<uint8_t>(rws::SET_SPEED);
uint8_t* serPtr = writeBuffer.data() + 1;
int32_t speedToSet = 0;
uint16_t rampTimeToSet = 10;
{
MutexGuard mg(ipcLock);
speedToSet = rwCookies[rwIdx]->currentRwSpeed;
rampTimeToSet = rwCookies[rwIdx]->currentRampTime;
}
size_t serLen = 1;
SerializeAdapter::serialize(&speedToSet, &serPtr, &serLen, writeBuffer.size(),
SerializeIF::Endianness::LITTLE);
SerializeAdapter::serialize(&rampTimeToSet, &serPtr, &serLen, writeBuffer.size(),
SerializeIF::Endianness::LITTLE);
uint16_t crc = CRC::crc16ccitt(writeBuffer.data(), 7, 0xFFFF);
writeBuffer[7] = static_cast<uint8_t>(crc & 0xFF);
writeBuffer[8] = static_cast<uint8_t>((crc >> 8) & 0xFF);
writeLen = 9;
return returnvalue::OK;
}

View File

@ -0,0 +1,89 @@
#ifndef LINUX_DEVICES_RWPOLLINGTASK_H_
#define LINUX_DEVICES_RWPOLLINGTASK_H_
#include <fsfw/devicehandlers/DeviceCommunicationIF.h>
#include <fsfw/objectmanager/SystemObject.h>
#include <fsfw/tasks/ExecutableObjectIF.h>
#include <fsfw/tasks/SemaphoreIF.h>
#include <fsfw_hal/common/gpio/GpioIF.h>
#include <fsfw_hal/linux/spi/SpiComIF.h>
#include <fsfw_hal/linux/spi/SpiCookie.h>
#include "mission/devices/devicedefinitions/rwHelpers.h"
class RwCookie : public SpiCookie {
friend class RwPollingTask;
public:
static constexpr size_t REPLY_BUF_LEN = 524;
RwCookie(uint8_t rwIdx, address_t spiAddress, gpioId_t chipSelect, const size_t maxSize,
spi::SpiModes spiMode, uint32_t spiSpeed)
: SpiCookie(spiAddress, chipSelect, maxSize, spiMode, spiSpeed), rwIdx(rwIdx) {}
private:
std::array<uint8_t, REPLY_BUF_LEN> replyBuf{};
bool setSpeed = true;
int32_t currentRwSpeed = 0;
uint16_t currentRampTime = 0;
rws::SpecialRwRequest specialRequest = rws::SpecialRwRequest::REQUEST_NONE;
uint8_t rwIdx;
};
class RwPollingTask : public SystemObject, public ExecutableObjectIF, public DeviceCommunicationIF {
public:
RwPollingTask(object_id_t objectId, const char* spiDev, GpioIF& gpioIF);
ReturnValue_t performOperation(uint8_t operationCode) override;
ReturnValue_t initialize() override;
private:
enum class InternalState { IDLE, BUSY } state = InternalState::IDLE;
SemaphoreIF* semaphore;
bool debugMode = false;
bool modeAndSpeedWasSet = false;
MutexIF* ipcLock;
MutexIF* spiLock;
const char* spiDev;
GpioIF& gpioIF;
std::array<bool, 4> skipCommandingForRw;
std::array<DeviceCommandId_t, 4> specialRequestIds;
std::array<RwCookie*, 4> rwCookies;
std::array<uint8_t, rws::MAX_CMD_SIZE> writeBuffer;
std::array<uint8_t, rws::MAX_CMD_SIZE * 2> encodedBuffer;
size_t writeLen = 0;
static constexpr MutexIF::TimeoutType TIMEOUT_TYPE = MutexIF::TimeoutType::WAITING;
static constexpr uint32_t TIMEOUT_MS = 20;
static constexpr uint8_t MAX_RETRIES_REPLY = 5;
ReturnValue_t writeAndReadAllRws(DeviceCommandId_t id);
ReturnValue_t writeOneRwCmd(uint8_t rwIdx, int fd);
ReturnValue_t readAllRws(DeviceCommandId_t id);
ReturnValue_t sendOneMessage(int fd, RwCookie& rwCookie);
ReturnValue_t readNextReply(RwCookie& rwCookie, uint8_t* replyBuf, size_t maxReplyLen);
void handleSpecialRequests();
ReturnValue_t initializeInterface(CookieIF* cookie) override;
ReturnValue_t sendMessage(CookieIF* cookie, const uint8_t* sendData, size_t sendLen) override;
ReturnValue_t getSendSuccess(CookieIF* cookie) override;
ReturnValue_t requestReceiveMessage(CookieIF* cookie, size_t requestLen) override;
ReturnValue_t readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) override;
ReturnValue_t openSpi(int flags, int& fd);
ReturnValue_t pullCsLow(gpioId_t gpioId, GpioIF& gpioIF);
void prepareSimpleCommand(DeviceCommandId_t id);
ReturnValue_t prepareSetSpeedCmd(uint8_t rwIdx);
size_t idAndIdxToReadBuffer(DeviceCommandId_t id, uint8_t rwIdx, uint8_t** readPtr);
void fillSpecialRequestArray();
void setAllReadFlagsFalse();
void pullCsHigh(gpioId_t gpioId, GpioIF& gpioIF);
void closeSpi(int);
};
#endif /* LINUX_DEVICES_RWPOLLINGTASK_H_ */

View File

@ -1,7 +1,7 @@
/** /**
* @brief Auto-generated event translation file. Contains 256 translations. * @brief Auto-generated event translation file. Contains 256 translations.
* @details * @details
* Generated on: 2023-02-13 10:07:30 * Generated on: 2023-02-17 02:12:04
*/ */
#include "translateEvents.h" #include "translateEvents.h"

View File

@ -47,7 +47,7 @@ enum sourceObjects : uint32_t {
GPIO_IF = 0x49010005, GPIO_IF = 0x49010005,
/* Custom device handler */ /* Custom device handler */
SPI_RW_COM_IF = 0x49020005, RW_POLLING_TASK = 0x49020005,
/* 0x54 ('T') for test handlers */ /* 0x54 ('T') for test handlers */
TEST_TASK = 0x54694269, TEST_TASK = 0x54694269,

View File

@ -2,7 +2,7 @@
* @brief Auto-generated object translation file. * @brief Auto-generated object translation file.
* @details * @details
* Contains 152 translations. * Contains 152 translations.
* Generated on: 2023-02-13 10:07:30 * Generated on: 2023-02-17 02:12:04
*/ */
#include "translateObjects.h" #include "translateObjects.h"
@ -84,7 +84,7 @@ const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF";
const char *GPIO_IF_STRING = "GPIO_IF"; const char *GPIO_IF_STRING = "GPIO_IF";
const char *SCEX_UART_READER_STRING = "SCEX_UART_READER"; const char *SCEX_UART_READER_STRING = "SCEX_UART_READER";
const char *SPI_MAIN_COM_IF_STRING = "SPI_MAIN_COM_IF"; const char *SPI_MAIN_COM_IF_STRING = "SPI_MAIN_COM_IF";
const char *SPI_RW_COM_IF_STRING = "SPI_RW_COM_IF"; const char *RW_POLLING_TASK_STRING = "RW_POLLING_TASK";
const char *SPI_RTD_COM_IF_STRING = "SPI_RTD_COM_IF"; const char *SPI_RTD_COM_IF_STRING = "SPI_RTD_COM_IF";
const char *UART_COM_IF_STRING = "UART_COM_IF"; const char *UART_COM_IF_STRING = "UART_COM_IF";
const char *I2C_COM_IF_STRING = "I2C_COM_IF"; const char *I2C_COM_IF_STRING = "I2C_COM_IF";
@ -318,7 +318,7 @@ const char *translateObject(object_id_t object) {
case 0x49020004: case 0x49020004:
return SPI_MAIN_COM_IF_STRING; return SPI_MAIN_COM_IF_STRING;
case 0x49020005: case 0x49020005:
return SPI_RW_COM_IF_STRING; return RW_POLLING_TASK_STRING;
case 0x49020006: case 0x49020006:
return SPI_RTD_COM_IF_STRING; return SPI_RTD_COM_IF_STRING;
case 0x49030003: case 0x49030003:

View File

@ -193,108 +193,106 @@ ReturnValue_t pst::pstTcsAndAcs(FixedTimeslotTaskIF *thisSequence, AcsPstCfg cfg
if (cfg.scheduleAcsBoard) { if (cfg.scheduleAcsBoard) {
if (enableAside) { if (enableAside) {
// A side // A side
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::GET_WRITE); DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::SEND_READ); DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::MGM_0_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::GET_READ); DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_WRITE); length * config::acs::SCHED_BLOCK_2_PERIOD, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::SEND_READ); length * config::acs::SCHED_BLOCK_2_PERIOD, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER, thisSequence->addSlot(objects::MGM_1_RM3100_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ); length * config::acs::SCHED_BLOCK_2_PERIOD, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_WRITE); length * config::acs::SCHED_BLOCK_2_PERIOD, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::SEND_READ); length * config::acs::SCHED_BLOCK_2_PERIOD, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER, thisSequence->addSlot(objects::GYRO_0_ADIS_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ); length * config::acs::SCHED_BLOCK_2_PERIOD, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::GET_WRITE); DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::SEND_READ); DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::GYRO_1_L3G_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::GET_READ); DeviceHandlerIF::GET_READ);
} }
if (enableBside) { if (enableBside) {
// B side // B side
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::GET_WRITE); DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::SEND_READ); DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::MGM_2_LIS3_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::GET_READ); DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_WRITE); length * config::acs::SCHED_BLOCK_2_PERIOD, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::SEND_READ); length * config::acs::SCHED_BLOCK_2_PERIOD, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER, thisSequence->addSlot(objects::MGM_3_RM3100_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ); length * config::acs::SCHED_BLOCK_2_PERIOD, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_WRITE); length * config::acs::SCHED_BLOCK_2_PERIOD, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::SEND_READ); length * config::acs::SCHED_BLOCK_2_PERIOD, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER, thisSequence->addSlot(objects::GYRO_2_ADIS_HANDLER,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ); length * config::acs::SCHED_BLOCK_2_PERIOD, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::GET_WRITE); DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::SEND_READ); DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * config::acs::SCHED_BLOCK_1_PERIOD, thisSequence->addSlot(objects::GYRO_3_L3G_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD,
DeviceHandlerIF::GET_READ); DeviceHandlerIF::GET_READ);
} }
} }
// SUS: 16 ms // SUS: 16 ms
bool addSus0 = true; bool addSus0 = true;
bool addSus1 = true; bool addSus1 = true;
bool addSus2 = true; bool addSus2 = true;
@ -442,7 +440,6 @@ ReturnValue_t pst::pstTcsAndAcs(FixedTimeslotTaskIF *thisSequence, AcsPstCfg cfg
thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ); length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ);
} }
if (addSus6) { if (addSus6) {
thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0, thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
@ -465,7 +462,6 @@ ReturnValue_t pst::pstTcsAndAcs(FixedTimeslotTaskIF *thisSequence, AcsPstCfg cfg
thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ); length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ);
} }
if (addSus7) { if (addSus7) {
thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0, thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
@ -488,7 +484,6 @@ ReturnValue_t pst::pstTcsAndAcs(FixedTimeslotTaskIF *thisSequence, AcsPstCfg cfg
thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ); length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ);
} }
if (addSus8) { if (addSus8) {
thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0, thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
@ -511,7 +506,6 @@ ReturnValue_t pst::pstTcsAndAcs(FixedTimeslotTaskIF *thisSequence, AcsPstCfg cfg
thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ); length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ);
} }
if (addSus9) { if (addSus9) {
thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0, thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
@ -523,6 +517,7 @@ ReturnValue_t pst::pstTcsAndAcs(FixedTimeslotTaskIF *thisSequence, AcsPstCfg cfg
DeviceHandlerIF::SEND_READ); DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0, thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0,
DeviceHandlerIF::GET_READ); DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF,
length * config::acs::SCHED_BLOCK_1_PERIOD, length * config::acs::SCHED_BLOCK_1_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
@ -533,7 +528,6 @@ ReturnValue_t pst::pstTcsAndAcs(FixedTimeslotTaskIF *thisSequence, AcsPstCfg cfg
thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ); length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ);
} }
if (addSus10) { if (addSus10) {
thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0, thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
@ -556,7 +550,6 @@ ReturnValue_t pst::pstTcsAndAcs(FixedTimeslotTaskIF *thisSequence, AcsPstCfg cfg
thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF,
length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ); length * config::acs::SCHED_BLOCK_1_PERIOD, DeviceHandlerIF::GET_READ);
} }
if (addSus11) { if (addSus11) {
thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0, thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
@ -623,68 +616,71 @@ ReturnValue_t pst::pstTcsAndAcs(FixedTimeslotTaskIF *thisSequence, AcsPstCfg cfg
DeviceHandlerIF::GET_READ); DeviceHandlerIF::GET_READ);
} }
thisSequence->addSlot(objects::ACS_CONTROLLER, length * config::acs::SCHED_BLOCK_2_PERIOD, 0); thisSequence->addSlot(objects::ACS_CONTROLLER, length * config::acs::SCHED_BLOCK_3_PERIOD, 0);
if (cfg.scheduleImtq) { if (cfg.scheduleImtq) {
// This is the torquing cycle. // This is the torquing cycle.
thisSequence->addSlot(objects::IMTQ_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::IMTQ_HANDLER, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::IMTQ_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::IMTQ_HANDLER, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::IMTQ_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::IMTQ_HANDLER, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_WRITE); DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::IMTQ_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::IMTQ_HANDLER, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_READ); DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::IMTQ_HANDLER, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::IMTQ_HANDLER, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_READ); DeviceHandlerIF::GET_READ);
} }
if (cfg.scheduleRws) { if (cfg.scheduleRws) {
thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_2_PERIOD, // this is the torquing cycle
thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION); DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_WRITE); DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_WRITE); DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_WRITE); DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_WRITE); DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_WRITE); DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_5_PERIOD,
DeviceHandlerIF::SEND_READ); DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_5_PERIOD,
DeviceHandlerIF::SEND_READ); DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_5_PERIOD,
DeviceHandlerIF::SEND_READ); DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_5_PERIOD,
DeviceHandlerIF::SEND_READ); DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_5_PERIOD,
DeviceHandlerIF::GET_READ); DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_5_PERIOD,
DeviceHandlerIF::GET_READ); DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_5_PERIOD,
DeviceHandlerIF::GET_READ); DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_2_PERIOD, thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_5_PERIOD,
DeviceHandlerIF::GET_READ); DeviceHandlerIF::GET_READ);
} }
thisSequence->addSlot(objects::SPI_RTD_COM_IF, length * 0.5, 0); thisSequence->addSlot(objects::SPI_RTD_COM_IF, length * 0.5, 0);
return returnvalue::OK; return returnvalue::OK;
} }

View File

@ -57,7 +57,8 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="thirdparty/json/tests|thirdparty/json/docs|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-release-q7s|bsp_linux_board|thirdparty/json/single_include|cmake-build-debug-q7s-em|cmake-build-debug-q7s/_deps/etl-src/temp|thirdparty/rapidcsv/examples|cmake-build-debug-q7s/_deps/etl-src/images|fsfwconfig|cmake-build-debug-q7s/_deps/etl-src/subprojects|thirdparty/json/third_party|bsp_q7s|thirdparty/json/test|bsp_te0720_1cfa|scripts|cmake-build-debug-q7s/_deps/etl-src/cmake|bsp_egse|build-Debug-RPi|thirdparty/rapidcsv/doc|thirdparty/json/doc|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-release-q7s-em|cmake-build-debug-q7s|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/test|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug/_deps|thirdparty/rapidcsv/tests|archive|thirdparty/json/cmake|thirdparty/json/benchmarks" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="cmake-build-debug-q7s-em|cmake-build-debug-q7s|bsp_q7s|cmake-build-debug/_deps|cmake-build-release-q7s-em|build-Debug-RPi|bsp_linux_board|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/subprojects|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-debug-q7s/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|scripts|bsp_te0720_1cfa|thirdparty/rapidcsv/tests|thirdparty/rapidcsv/examples|thirdparty/rapidcsv/doc|thirdparty/json/third_party|thirdparty/json/test|thirdparty/json/single_include|thirdparty/json/doc|thirdparty/json/cmake|thirdparty/json/benchmarks|archive|cmake-build-release-q7s|bsp_egse|cmake-build-debug-q7s/_deps/etl-src/test|fsfwconfig" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
<entry flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name="cmake-build-debug/_deps/etl-src/include"/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -119,7 +120,8 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="thirdparty/json/tests|thirdparty/json/docs|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-release-q7s|bsp_linux_board|thirdparty/json/single_include|cmake-build-debug-q7s-em|cmake-build-debug-q7s/_deps/etl-src/temp|thirdparty/rapidcsv/examples|cmake-build-debug-q7s/_deps/etl-src/images|fsfwconfig|cmake-build-debug-q7s/_deps/etl-src/subprojects|thirdparty/json/third_party|bsp_q7s|thirdparty/json/test|bsp_te0720_1cfa|scripts|cmake-build-debug-q7s/_deps/etl-src/cmake|bsp_egse|build-Debug-RPi|thirdparty/rapidcsv/doc|thirdparty/json/doc|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-release-q7s-em|cmake-build-debug-q7s|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/test|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug/_deps|thirdparty/rapidcsv/tests|archive|thirdparty/json/cmake|thirdparty/json/benchmarks" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="cmake-build-debug-q7s-em|cmake-build-debug-q7s|bsp_q7s|cmake-build-debug/_deps|cmake-build-release-q7s-em|build-Debug-RPi|bsp_linux_board|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/subprojects|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-debug-q7s/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|scripts|bsp_te0720_1cfa|thirdparty/rapidcsv/tests|thirdparty/rapidcsv/examples|thirdparty/rapidcsv/doc|thirdparty/json/third_party|thirdparty/json/test|thirdparty/json/single_include|thirdparty/json/doc|thirdparty/json/cmake|thirdparty/json/benchmarks|archive|cmake-build-release-q7s|bsp_egse|cmake-build-debug-q7s/_deps/etl-src/test|fsfwconfig" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
<entry flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name="cmake-build-debug/_deps/etl-src/include"/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -187,7 +189,8 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="thirdparty/json/tests|thirdparty/json/docs|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-release-q7s|bsp_linux_board|thirdparty/json/single_include|cmake-build-debug-q7s-em|cmake-build-debug-q7s/_deps/etl-src/temp|thirdparty/rapidcsv/examples|cmake-build-debug-q7s/_deps/etl-src/images|fsfwconfig|cmake-build-debug-q7s/_deps/etl-src/subprojects|thirdparty/json/third_party|bsp_q7s|thirdparty/json/test|bsp_te0720_1cfa|scripts|cmake-build-debug-q7s/_deps/etl-src/cmake|bsp_egse|build-Debug-RPi|thirdparty/rapidcsv/doc|thirdparty/json/doc|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-release-q7s-em|cmake-build-debug-q7s|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/test|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug/_deps|thirdparty/rapidcsv/tests|archive|thirdparty/json/cmake|thirdparty/json/benchmarks" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="cmake-build-debug-q7s-em|cmake-build-debug-q7s|bsp_q7s|cmake-build-debug/_deps|cmake-build-release-q7s-em|build-Debug-RPi|bsp_linux_board|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/subprojects|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-debug-q7s/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|scripts|bsp_te0720_1cfa|thirdparty/rapidcsv/tests|thirdparty/rapidcsv/examples|thirdparty/rapidcsv/doc|thirdparty/json/third_party|thirdparty/json/test|thirdparty/json/single_include|thirdparty/json/doc|thirdparty/json/cmake|thirdparty/json/benchmarks|archive|cmake-build-release-q7s|bsp_egse|cmake-build-debug-q7s/_deps/etl-src/test|fsfwconfig" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
<entry flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name="cmake-build-debug/_deps/etl-src/include"/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -255,7 +258,8 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="thirdparty/json/tests|thirdparty/json/docs|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-release-q7s|bsp_linux_board|thirdparty/json/single_include|cmake-build-debug-q7s-em|cmake-build-debug-q7s/_deps/etl-src/temp|thirdparty/rapidcsv/examples|cmake-build-debug-q7s/_deps/etl-src/images|fsfwconfig|cmake-build-debug-q7s/_deps/etl-src/subprojects|thirdparty/json/third_party|bsp_q7s|thirdparty/json/test|bsp_te0720_1cfa|scripts|cmake-build-debug-q7s/_deps/etl-src/cmake|bsp_egse|build-Debug-RPi|thirdparty/rapidcsv/doc|thirdparty/json/doc|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-release-q7s-em|cmake-build-debug-q7s|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/test|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug/_deps|thirdparty/rapidcsv/tests|archive|thirdparty/json/cmake|thirdparty/json/benchmarks" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="cmake-build-debug-q7s-em|cmake-build-debug-q7s|bsp_q7s|cmake-build-debug/_deps|cmake-build-release-q7s-em|build-Debug-RPi|bsp_linux_board|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/subprojects|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-debug-q7s/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|scripts|bsp_te0720_1cfa|thirdparty/rapidcsv/tests|thirdparty/rapidcsv/examples|thirdparty/rapidcsv/doc|thirdparty/json/third_party|thirdparty/json/test|thirdparty/json/single_include|thirdparty/json/doc|thirdparty/json/cmake|thirdparty/json/benchmarks|archive|cmake-build-release-q7s|bsp_egse|cmake-build-debug-q7s/_deps/etl-src/test|fsfwconfig" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
<entry flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name="cmake-build-debug/_deps/etl-src/include"/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -418,7 +422,8 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="thirdparty/json/tests|thirdparty/json/docs|build-Debug-RPi/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-release-q7s|build-Debug-RPi/_deps/etl-src/temp|thirdparty/json/single_include|cmake-build-debug-q7s-em|cmake-build-debug-q7s/_deps/etl-src/temp|thirdparty/rapidcsv/examples|build-Debug-RPi/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/images|build-Debug-RPi/_deps/etl-src/subprojects|cmake-build-debug|cmake-build-debug-q7s/_deps/etl-src/subprojects|thirdparty/json/third_party|bsp_hosted|thirdparty/json/test|bsp_te0720_1cfa|scripts|build-Debug-RPi/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/cmake|bsp_egse|thirdparty/rapidcsv/doc|build-Debug-RPi/_deps/etl-src/examples|thirdparty/json/doc|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-release-q7s-em|build-Debug-RPi/_deps/etl-src/test|build-Debug-RPi/_deps/etl-src/scripts|cmake-build-debug-q7s|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/test|build-Debug-RPi/_deps/etl-src/arduino|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|build-Debug-RPi/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/support|thirdparty/rapidcsv/tests|archive|thirdparty/json/cmake|thirdparty/json/benchmarks" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="build-Debug-RPi/_deps/etl-src/uml|build-Debug-RPi/_deps/etl-src/test|build-Debug-RPi/_deps/etl-src/temp|build-Debug-RPi/_deps/etl-src/support|build-Debug-RPi/_deps/etl-src/subprojects|build-Debug-RPi/_deps/etl-src/scripts|build-Debug-RPi/_deps/etl-src/images|build-Debug-RPi/_deps/etl-src/examples|build-Debug-RPi/_deps/etl-src/cmake|build-Debug-RPi/_deps/etl-src/arduino|cmake-build-debug-q7s|cmake-build-debug|cmake-build-debug-q7s-em|cmake-build-release-q7s-em|bsp_hosted|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/subprojects|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-debug-q7s/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|scripts|bsp_te0720_1cfa|thirdparty/rapidcsv/tests|thirdparty/rapidcsv/examples|thirdparty/rapidcsv/doc|thirdparty/json/third_party|thirdparty/json/test|thirdparty/json/single_include|thirdparty/json/doc|thirdparty/json/cmake|thirdparty/json/benchmarks|archive|cmake-build-release-q7s|bsp_egse|cmake-build-debug-q7s/_deps/etl-src/test" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
<entry flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name="cmake-build-debug/_deps/etl-src/include"/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -580,7 +585,8 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="thirdparty/json/tests|thirdparty/json/docs|build-Debug-RPi/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-release-q7s|build-Debug-RPi/_deps/etl-src/temp|thirdparty/json/single_include|cmake-build-debug-q7s-em|cmake-build-debug-q7s/_deps/etl-src/temp|thirdparty/rapidcsv/examples|build-Debug-RPi/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/images|build-Debug-RPi/_deps/etl-src/subprojects|cmake-build-debug|cmake-build-debug-q7s/_deps/etl-src/subprojects|thirdparty/json/third_party|bsp_hosted|thirdparty/json/test|bsp_te0720_1cfa|scripts|build-Debug-RPi/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/cmake|bsp_egse|thirdparty/rapidcsv/doc|build-Debug-RPi/_deps/etl-src/examples|thirdparty/json/doc|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-release-q7s-em|build-Debug-RPi/_deps/etl-src/test|build-Debug-RPi/_deps/etl-src/scripts|cmake-build-debug-q7s|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/test|build-Debug-RPi/_deps/etl-src/arduino|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|build-Debug-RPi/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/support|thirdparty/rapidcsv/tests|archive|thirdparty/json/cmake|thirdparty/json/benchmarks" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="build-Debug-RPi/_deps/etl-src/uml|build-Debug-RPi/_deps/etl-src/test|build-Debug-RPi/_deps/etl-src/temp|build-Debug-RPi/_deps/etl-src/support|build-Debug-RPi/_deps/etl-src/subprojects|build-Debug-RPi/_deps/etl-src/scripts|build-Debug-RPi/_deps/etl-src/images|build-Debug-RPi/_deps/etl-src/examples|build-Debug-RPi/_deps/etl-src/cmake|build-Debug-RPi/_deps/etl-src/arduino|cmake-build-debug-q7s|cmake-build-debug|cmake-build-debug-q7s-em|cmake-build-release-q7s-em|bsp_hosted|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/subprojects|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-debug-q7s/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|scripts|bsp_te0720_1cfa|thirdparty/rapidcsv/tests|thirdparty/rapidcsv/examples|thirdparty/rapidcsv/doc|thirdparty/json/third_party|thirdparty/json/test|thirdparty/json/single_include|thirdparty/json/doc|thirdparty/json/cmake|thirdparty/json/benchmarks|archive|cmake-build-release-q7s|bsp_egse|cmake-build-debug-q7s/_deps/etl-src/test" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
<entry flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name="cmake-build-debug/_deps/etl-src/include"/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -680,7 +686,7 @@
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.other.1721137382" name="Other debugging flags" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.other"/> <option id="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.other.1721137382" name="Other debugging flags" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.debugging.other"/>
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.showDevicesTab.2014131279" name="showDevicesTab" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.showDevicesTab"/> <option id="ilg.gnuarmeclipse.managedbuild.cross.option.showDevicesTab.2014131279" name="showDevicesTab" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.showDevicesTab"/>
<targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="ilg.gnuarmeclipse.managedbuild.cross.targetPlatform.363832829" isAbstract="false" osList="all" superClass="ilg.gnuarmeclipse.managedbuild.cross.targetPlatform"/> <targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.ELF" id="ilg.gnuarmeclipse.managedbuild.cross.targetPlatform.363832829" isAbstract="false" osList="all" superClass="ilg.gnuarmeclipse.managedbuild.cross.targetPlatform"/>
<builder arguments="--build . -j" buildPath="${workspace_loc:/eive-obsw/cmake-build-debug-q7s}" command="cmake" enableCleanBuild="false" enabledIncrementalBuild="true" id="ilg.gnuarmeclipse.managedbuild.cross.builder.1895725167" incrementalBuildTarget="" keepEnvironmentInBuildfile="false" managedBuildOn="false" name="Gnu Make Builder" parallelBuildOn="true" parallelizationNumber="optimal" superClass="ilg.gnuarmeclipse.managedbuild.cross.builder"/> <builder arguments="--build . -j 10" buildPath="${workspace_loc:/eive-obsw/cmake-build-debug-q7s}" command="cmake" enableCleanBuild="false" enabledIncrementalBuild="true" id="ilg.gnuarmeclipse.managedbuild.cross.builder.1895725167" incrementalBuildTarget="" keepEnvironmentInBuildfile="false" managedBuildOn="false" name="Gnu Make Builder" parallelBuildOn="true" parallelizationNumber="optimal" superClass="ilg.gnuarmeclipse.managedbuild.cross.builder"/>
<tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.assembler.2035413172" name="GNU Arm Cross Assembler" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.assembler"> <tool id="ilg.gnuarmeclipse.managedbuild.cross.tool.assembler.2035413172" name="GNU Arm Cross Assembler" superClass="ilg.gnuarmeclipse.managedbuild.cross.tool.assembler">
<option id="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.usepreprocessor.1527860624" name="Use preprocessor" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.usepreprocessor" value="true" valueType="boolean"/> <option id="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.usepreprocessor.1527860624" name="Use preprocessor" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.usepreprocessor" value="true" valueType="boolean"/>
<option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.include.paths.1772224733" name="Include paths (-I)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.include.paths" valueType="includePath"> <option IS_BUILTIN_EMPTY="false" IS_VALUE_EMPTY="false" id="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.include.paths.1772224733" name="Include paths (-I)" superClass="ilg.gnuarmeclipse.managedbuild.cross.option.assembler.include.paths" valueType="includePath">
@ -750,7 +756,8 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="thirdparty/json/tests|thirdparty/json/docs|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-release-q7s|bsp_linux_board|thirdparty/json/single_include|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s-em|thirdparty/rapidcsv/examples|build-Debug-Host|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug|cmake-build-debug-q7s/_deps/etl-src/subprojects|thirdparty/json/third_party|bsp_hosted|thirdparty/json/test|bsp_te0720_1cfa|scripts|cmake-build-debug-q7s/_deps/etl-src/cmake|bsp_egse|build-Debug-RPi|thirdparty/rapidcsv/doc|thirdparty/json/doc|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-release-q7s-em|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/test|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|cmake-build-debug-q7s/_deps/etl-src/support|thirdparty/rapidcsv/tests|archive|build-Watchdog-Debug|thirdparty/json/cmake|thirdparty/json/benchmarks" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="cmake-build-debug-q7s|cmake-build-release-q7s-em|build-Debug-RPi|bsp_hosted|bsp_linux_board|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/subprojects|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-debug-q7s/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|scripts|bsp_te0720_1cfa|thirdparty/rapidcsv/tests|thirdparty/rapidcsv/examples|thirdparty/rapidcsv/doc|thirdparty/json/third_party|thirdparty/json/test|thirdparty/json/single_include|thirdparty/json/doc|thirdparty/json/cmake|thirdparty/json/benchmarks|archive|cmake-build-release-q7s|bsp_egse|cmake-build-debug-q7s/_deps/etl-src/test|cmake-build-debug|cmake-build-debug-q7s-em|build-Debug-Host|build-Watchdog-Debug" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
<entry flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name="cmake-build-debug/_deps/etl-src/include"/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -917,7 +924,8 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="thirdparty/json/tests|thirdparty/json/docs|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-release-q7s/_deps/etl-src/support|bsp_linux_board|thirdparty/json/single_include|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s-em|thirdparty/rapidcsv/examples|build-Debug-Host|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug|cmake-build-debug-q7s/_deps/etl-src/subprojects|thirdparty/json/third_party|bsp_hosted|thirdparty/json/test|bsp_te0720_1cfa|scripts|cmake-build-release-q7s/_deps/etl-src/test|cmake-build-release-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/cmake|bsp_egse|cmake-build-release-q7s/_deps/etl-src/arduino|build-Debug-RPi|cmake-build-release-q7s/_deps/etl-src/cmake|thirdparty/rapidcsv/doc|thirdparty/json/doc|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-release-q7s-em|cmake-build-debug-q7s|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/test|cmake-build-release-q7s/_deps/etl-src/uml|cmake-build-release-q7s/_deps/etl-src/examples|cmake-build-debug-q7s/_deps/etl-src/arduino|cmake-build-release-q7s/_deps/etl-src/temp|tmtc|cmake-build-release-q7s/_deps/etl-src/images|cmake-build-release-q7s/_deps/etl-src/subprojects|cmake-build-debug-q7s/_deps/etl-src/support|thirdparty/rapidcsv/tests|archive|build-Watchdog-Debug|thirdparty/json/cmake|thirdparty/json/benchmarks" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="cmake-build-debug-q7s|cmake-build-release-q7s-em|cmake-build-release-q7s/_deps/etl-src/uml|cmake-build-release-q7s/_deps/etl-src/test|cmake-build-release-q7s/_deps/etl-src/temp|cmake-build-release-q7s/_deps/etl-src/support|cmake-build-release-q7s/_deps/etl-src/subprojects|cmake-build-release-q7s/_deps/etl-src/scripts|cmake-build-release-q7s/_deps/etl-src/images|cmake-build-release-q7s/_deps/etl-src/examples|cmake-build-release-q7s/_deps/etl-src/cmake|cmake-build-release-q7s/_deps/etl-src/arduino|build-Debug-RPi|bsp_hosted|bsp_linux_board|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/subprojects|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-debug-q7s/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|scripts|bsp_te0720_1cfa|thirdparty/rapidcsv/tests|thirdparty/rapidcsv/examples|thirdparty/rapidcsv/doc|thirdparty/json/third_party|thirdparty/json/test|thirdparty/json/single_include|thirdparty/json/doc|thirdparty/json/cmake|thirdparty/json/benchmarks|archive|bsp_egse|cmake-build-debug-q7s/_deps/etl-src/test|cmake-build-debug|cmake-build-debug-q7s-em|build-Debug-Host|build-Watchdog-Debug" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
<entry flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name="cmake-build-debug/_deps/etl-src/include"/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -1084,7 +1092,7 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="thirdparty/json/tests|thirdparty/json/docs|cmake-build-debug-q7s-em/_deps/etl-src/test|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-release-q7s|bsp_linux_board|thirdparty/json/single_include|cmake-build-debug-q7s/_deps/etl-src/temp|thirdparty/rapidcsv/examples|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/subprojects|thirdparty/json/third_party|bsp_hosted|thirdparty/json/test|bsp_te0720_1cfa|scripts|cmake-build-debug-q7s/_deps/etl-src/cmake|bsp_egse|build-Debug-RPi|thirdparty/rapidcsv/doc|thirdparty/json/doc|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-release-q7s-em|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/test|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|cmake-build-debug-q7s/_deps/etl-src/support|thirdparty/rapidcsv/tests|archive|thirdparty/json/cmake|thirdparty/json/benchmarks" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="cmake-build-debug/_deps/etl-src/uml|cmake-build-debug/_deps/etl-src/test|cmake-build-debug/_deps/etl-src/temp|cmake-build-debug/_deps/etl-src/support|cmake-build-debug/_deps/etl-src/subprojects|cmake-build-debug/_deps/etl-src/scripts|cmake-build-debug/_deps/etl-src/images|cmake-build-debug/_deps/etl-src/examples|cmake-build-debug/_deps/etl-src/cmake|cmake-build-debug/_deps/etl-src/arduino|cmake-build-release-q7s-em|build-Debug-RPi|bsp_hosted|bsp_linux_board|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/subprojects|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-debug-q7s/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|scripts|bsp_te0720_1cfa|thirdparty/rapidcsv/tests|thirdparty/rapidcsv/examples|thirdparty/rapidcsv/doc|thirdparty/json/third_party|thirdparty/json/test|thirdparty/json/single_include|thirdparty/json/doc|thirdparty/json/cmake|thirdparty/json/benchmarks|archive|cmake-build-release-q7s|bsp_egse|cmake-build-debug-q7s/_deps/etl-src/test" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -1149,7 +1157,7 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="thirdparty/json/tests|thirdparty/json/docs|cmake-build-debug-q7s-em/_deps/etl-src/test|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-release-q7s|bsp_linux_board|thirdparty/json/single_include|cmake-build-debug-q7s/_deps/etl-src/temp|thirdparty/rapidcsv/examples|cmake-build-debug-q7s/_deps/etl-src/images|fsfwconfig|cmake-build-debug-q7s/_deps/etl-src/subprojects|thirdparty/json/third_party|thirdparty/json/test|bsp_te0720_1cfa|scripts|cmake-build-debug-q7s/_deps/etl-src/cmake|bsp_egse|build-Debug-RPi|thirdparty/rapidcsv/doc|thirdparty/json/doc|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-release-q7s-em|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/test|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|cmake-build-debug-q7s/_deps/etl-src/support|thirdparty/rapidcsv/tests|archive|thirdparty/json/cmake|thirdparty/json/benchmarks" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="cmake-build-debug/_deps/etl-src/uml|cmake-build-debug/_deps/etl-src/test|cmake-build-debug/_deps/etl-src/temp|cmake-build-debug/_deps/etl-src/support|cmake-build-debug/_deps/etl-src/subprojects|cmake-build-debug/_deps/etl-src/scripts|cmake-build-debug/_deps/etl-src/images|cmake-build-debug/_deps/etl-src/examples|cmake-build-debug/_deps/etl-src/cmake|cmake-build-debug/_deps/etl-src/arduino|cmake-build-release-q7s-em|build-Debug-RPi|bsp_linux_board|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/subprojects|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-debug-q7s/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|scripts|bsp_te0720_1cfa|thirdparty/rapidcsv/tests|thirdparty/rapidcsv/examples|thirdparty/rapidcsv/doc|thirdparty/json/third_party|thirdparty/json/test|thirdparty/json/single_include|thirdparty/json/doc|thirdparty/json/cmake|thirdparty/json/benchmarks|archive|cmake-build-release-q7s|bsp_egse|cmake-build-debug-q7s/_deps/etl-src/test|fsfwconfig" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -1317,7 +1325,8 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="thirdparty/json/tests|thirdparty/json/docs|cmake-build-debug-q7s-em/_deps/etl-src/test|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-release-q7s|bsp_linux_board|thirdparty/json/single_include|cmake-build-debug-q7s/_deps/etl-src/temp|thirdparty/rapidcsv/examples|build-Debug-Host|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug|cmake-build-debug-q7s/_deps/etl-src/subprojects|thirdparty/json/third_party|bsp_hosted|thirdparty/json/test|bsp_te0720_1cfa|scripts|cmake-build-debug-q7s/_deps/etl-src/cmake|bsp_egse|build-Debug-RPi|thirdparty/rapidcsv/doc|thirdparty/json/doc|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-release-q7s-em|cmake-build-debug-q7s|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/test|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|cmake-build-debug-q7s/_deps/etl-src/support|thirdparty/rapidcsv/tests|archive|build-Watchdog-Debug|thirdparty/json/cmake|thirdparty/json/benchmarks" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="cmake-build-debug-q7s|cmake-build-release-q7s-em|build-Debug-RPi|bsp_hosted|bsp_linux_board|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/subprojects|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-debug-q7s/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|scripts|bsp_te0720_1cfa|thirdparty/rapidcsv/tests|thirdparty/rapidcsv/examples|thirdparty/rapidcsv/doc|thirdparty/json/third_party|thirdparty/json/test|thirdparty/json/single_include|thirdparty/json/doc|thirdparty/json/cmake|thirdparty/json/benchmarks|archive|cmake-build-release-q7s|bsp_egse|cmake-build-debug-q7s/_deps/etl-src/test|cmake-build-debug|build-Debug-Host|build-Watchdog-Debug" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
<entry flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name="cmake-build-debug/_deps/etl-src/include"/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -1386,7 +1395,7 @@
</toolChain> </toolChain>
</folderInfo> </folderInfo>
<sourceEntries> <sourceEntries>
<entry excluding="thirdparty/json/tests|thirdparty/json/docs|cmake-build-debug-q7s-em/_deps/etl-src/test|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-release-q7s|bsp_linux_board|thirdparty/json/single_include|cmake-build-debug-q7s/_deps/etl-src/temp|thirdparty/rapidcsv/examples|cmake-build-debug-q7s/_deps/etl-src/images|fsfwconfig|cmake-build-debug-q7s/_deps/etl-src/subprojects|thirdparty/json/third_party|thirdparty/json/test|bsp_te0720_1cfa|scripts|cmake-build-debug-q7s/_deps/etl-src/cmake|bsp_egse|build-Debug-RPi|thirdparty/rapidcsv/doc|thirdparty/json/doc|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-release-q7s-em|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/test|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|cmake-build-debug-q7s/_deps/etl-src/support|thirdparty/rapidcsv/tests|archive|thirdparty/json/cmake|thirdparty/json/benchmarks" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/> <entry excluding="cmake-build-debug/_deps/etl-src/uml|cmake-build-debug/_deps/etl-src/test|cmake-build-debug/_deps/etl-src/temp|cmake-build-debug/_deps/etl-src/support|cmake-build-debug/_deps/etl-src/subprojects|cmake-build-debug/_deps/etl-src/scripts|cmake-build-debug/_deps/etl-src/images|cmake-build-debug/_deps/etl-src/examples|cmake-build-debug/_deps/etl-src/cmake|cmake-build-debug/_deps/etl-src/arduino|cmake-build-release-q7s-em|build-Debug-RPi|bsp_linux_board|cmake-build-debug-q7s/_deps/etl-src/uml|cmake-build-debug-q7s/_deps/etl-src/temp|cmake-build-debug-q7s/_deps/etl-src/support|cmake-build-debug-q7s/_deps/etl-src/subprojects|cmake-build-debug-q7s/_deps/etl-src/scripts|cmake-build-debug-q7s/_deps/etl-src/images|cmake-build-debug-q7s/_deps/etl-src/examples|cmake-build-debug-q7s/_deps/etl-src/cmake|cmake-build-debug-q7s/_deps/etl-src/arduino|tmtc|scripts|bsp_te0720_1cfa|thirdparty/rapidcsv/tests|thirdparty/rapidcsv/examples|thirdparty/rapidcsv/doc|thirdparty/json/third_party|thirdparty/json/test|thirdparty/json/single_include|thirdparty/json/doc|thirdparty/json/cmake|thirdparty/json/benchmarks|archive|cmake-build-release-q7s|bsp_egse|cmake-build-debug-q7s/_deps/etl-src/test|fsfwconfig" flags="VALUE_WORKSPACE_PATH|RESOLVED" kind="sourcePath" name=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>

View File

@ -23,6 +23,8 @@ static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::ACS_SUBSYSTEM;
static const Event SAFE_RATE_VIOLATION = MAKE_EVENT(0, severity::MEDIUM); static const Event SAFE_RATE_VIOLATION = MAKE_EVENT(0, severity::MEDIUM);
//!< The system has recovered from a safe rate rotation violation. //!< The system has recovered from a safe rate rotation violation.
static constexpr Event SAFE_RATE_RECOVERY = MAKE_EVENT(1, severity::MEDIUM); static constexpr Event SAFE_RATE_RECOVERY = MAKE_EVENT(1, severity::MEDIUM);
//!< Multiple RWs are invalid, not commandable and therefore higher ACS modes cannot be maintained.
static constexpr Event MULTIPLE_RW_INVALID = MAKE_EVENT(2, severity::HIGH);
extern const char* getModeStr(AcsMode mode); extern const char* getModeStr(AcsMode mode);

View File

@ -15,6 +15,7 @@ AcsController::AcsController(object_id_t objectId)
detumble(&acsParameters), detumble(&acsParameters),
ptgCtrl(&acsParameters), ptgCtrl(&acsParameters),
detumbleCounter{0}, detumbleCounter{0},
multipleRwUnavailableCounter{0},
parameterHelper(this), parameterHelper(this),
mgmDataRaw(this), mgmDataRaw(this),
mgmDataProcessed(this), mgmDataProcessed(this),
@ -119,10 +120,10 @@ void AcsController::performSafe() {
navigation.useMekf(&sensorValues, &gyrDataProcessed, &mgmDataProcessed, &susDataProcessed, navigation.useMekf(&sensorValues, &gyrDataProcessed, &mgmDataProcessed, &susDataProcessed,
&mekfData, &validMekf); &mekfData, &validMekf);
// Give desired satellite rate and sun direction to align // give desired satellite rate and sun direction to align
double satRateSafe[3] = {0, 0, 0}, sunTargetDir[3] = {0, 0, 0}; double satRateSafe[3] = {0, 0, 0}, sunTargetDir[3] = {0, 0, 0};
guidance.getTargetParamsSafe(sunTargetDir, satRateSafe); guidance.getTargetParamsSafe(sunTargetDir, satRateSafe);
// IF MEKF is working // if MEKF is working
double magMomMtq[3] = {0, 0, 0}, errAng = 0.0; double magMomMtq[3] = {0, 0, 0}, errAng = 0.0;
bool magMomMtqValid = false; bool magMomMtqValid = false;
if (validMekf == returnvalue::OK) { if (validMekf == returnvalue::OK) {
@ -140,8 +141,8 @@ void AcsController::performSafe() {
sunTargetDir, satRateSafe, &errAng, magMomMtq, &magMomMtqValid); sunTargetDir, satRateSafe, &errAng, magMomMtq, &magMomMtqValid);
} }
double dipolCmdUnits[3] = {0, 0, 0}; int16_t cmdDipolMtqs[3] = {0, 0, 0};
actuatorCmd.cmdDipolMtq(magMomMtq, dipolCmdUnits); actuatorCmd.cmdDipolMtq(magMomMtq, cmdDipolMtqs);
{ {
PoolReadGuard pg(&ctrlValData); PoolReadGuard pg(&ctrlValData);
@ -183,18 +184,15 @@ void AcsController::performSafe() {
actuatorCmdData.rwTargetTorque.setValid(false); actuatorCmdData.rwTargetTorque.setValid(false);
std::memcpy(actuatorCmdData.rwTargetSpeed.value, zeroVec, 4 * sizeof(int32_t)); std::memcpy(actuatorCmdData.rwTargetSpeed.value, zeroVec, 4 * sizeof(int32_t));
actuatorCmdData.rwTargetSpeed.setValid(false); actuatorCmdData.rwTargetSpeed.setValid(false);
std::memcpy(actuatorCmdData.mtqTargetDipole.value, dipolCmdUnits, 3 * sizeof(int16_t)); std::memcpy(actuatorCmdData.mtqTargetDipole.value, cmdDipolMtqs, 3 * sizeof(int16_t));
actuatorCmdData.mtqTargetDipole.setValid(true); actuatorCmdData.mtqTargetDipole.setValid(true);
actuatorCmdData.setValidity(true, false); actuatorCmdData.setValidity(true, false);
} }
} }
// {
// PoolReadGuard pg(&dipoleSet); // commandActuators(cmdDipolMtqs[0], cmdDipolMtqs[1], cmdDipolMtqs[2],
// MutexGuard mg(torquer::lazyLock()); // acsParameters.magnetorquesParameter.torqueDuration, 0, 0, 0, 0,
// torquer::NEW_ACTUATION_FLAG = true; // acsParameters.rwHandlingParameters.rampTime);
// dipoleSet.setDipoles(cmdDipolUnits[0], cmdDipolUnits[1], cmdDipolUnits[2],
// torqueDuration);
// }
} }
void AcsController::performDetumble() { void AcsController::performDetumble() {
@ -211,8 +209,8 @@ void AcsController::performDetumble() {
detumble.bDotLaw(mgmDataProcessed.mgmVecTotDerivative.value, detumble.bDotLaw(mgmDataProcessed.mgmVecTotDerivative.value,
mgmDataProcessed.mgmVecTotDerivative.isValid(), mgmDataProcessed.mgmVecTot.value, mgmDataProcessed.mgmVecTotDerivative.isValid(), mgmDataProcessed.mgmVecTot.value,
mgmDataProcessed.mgmVecTot.isValid(), magMomMtq); mgmDataProcessed.mgmVecTot.isValid(), magMomMtq);
double dipolCmdUnits[3] = {0, 0, 0}; int16_t cmdDipolMtqs[3] = {0, 0, 0};
actuatorCmd.cmdDipolMtq(magMomMtq, dipolCmdUnits); actuatorCmd.cmdDipolMtq(magMomMtq, cmdDipolMtqs);
if (mekfData.satRotRateMekf.isValid() && if (mekfData.satRotRateMekf.isValid() &&
VectorOperations<double>::norm(mekfData.satRotRateMekf.value, 3) < VectorOperations<double>::norm(mekfData.satRotRateMekf.value, 3) <
@ -231,10 +229,6 @@ void AcsController::performDetumble() {
triggerEvent(acs::SAFE_RATE_RECOVERY); triggerEvent(acs::SAFE_RATE_RECOVERY);
} }
int16_t cmdDipolUnitsInt[3] = {0, 0, 0};
for (int i = 0; i < 3; ++i) {
cmdDipolUnitsInt[i] = std::round(dipolCmdUnits[i]);
}
{ {
PoolReadGuard pg(&actuatorCmdData); PoolReadGuard pg(&actuatorCmdData);
if (pg.getReadResult() == returnvalue::OK) { if (pg.getReadResult() == returnvalue::OK) {
@ -242,18 +236,15 @@ void AcsController::performDetumble() {
actuatorCmdData.rwTargetTorque.setValid(false); actuatorCmdData.rwTargetTorque.setValid(false);
std::memset(actuatorCmdData.rwTargetSpeed.value, 0, 4 * sizeof(int32_t)); std::memset(actuatorCmdData.rwTargetSpeed.value, 0, 4 * sizeof(int32_t));
actuatorCmdData.rwTargetSpeed.setValid(false); actuatorCmdData.rwTargetSpeed.setValid(false);
std::memcpy(actuatorCmdData.mtqTargetDipole.value, cmdDipolUnitsInt, 3 * sizeof(int16_t)); std::memcpy(actuatorCmdData.mtqTargetDipole.value, cmdDipolMtqs, 3 * sizeof(int16_t));
actuatorCmdData.mtqTargetDipole.setValid(true); actuatorCmdData.mtqTargetDipole.setValid(true);
actuatorCmdData.setValidity(true, false); actuatorCmdData.setValidity(true, false);
} }
} }
// {
// PoolReadGuard pg(&dipoleSet); // commandActuators(cmdDipolMtqs[0], cmdDipolMtqs[1], cmdDipolMtqs[2],
// MutexGuard mg(torquer::lazyLock()); // acsParameters.magnetorquesParameter.torqueDuration, 0, 0, 0, 0,
// torquer::NEW_ACTUATION_FLAG = true; // acsParameters.rwHandlingParameters.rampTime);
// dipoleSet.setDipoles(cmdDipolUnitsInt[0], cmdDipolUnitsInt[1], cmdDipolUnitsInt[2],
// torqueDuration);
// }
} }
void AcsController::performPointingCtrl() { void AcsController::performPointingCtrl() {
@ -273,10 +264,19 @@ void AcsController::performPointingCtrl() {
double quatErrorComplete[4] = {0, 0, 0, 0}, quatError[3] = {0, 0, 0}, double quatErrorComplete[4] = {0, 0, 0, 0}, quatError[3] = {0, 0, 0},
deltaRate[3] = {0, 0, 0}; // ToDo: check if pointer needed deltaRate[3] = {0, 0, 0}; // ToDo: check if pointer needed
double rwPseudoInv[4][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}, {0, 0, 0}}; double rwPseudoInv[4][3] = {{0, 0, 0}, {0, 0, 0}, {0, 0, 0}, {0, 0, 0}};
guidance.getDistributionMatrixRw(&sensorValues, *rwPseudoInv); ReturnValue_t result = guidance.getDistributionMatrixRw(&sensorValues, *rwPseudoInv);
if (result == returnvalue::FAILED) {
multipleRwUnavailableCounter++;
if (multipleRwUnavailableCounter > 4) {
triggerEvent(acs::MULTIPLE_RW_INVALID);
}
return;
} else {
multipleRwUnavailableCounter = 0;
}
double torquePtgRws[4] = {0, 0, 0, 0}, rwTrqNs[4] = {0, 0, 0, 0}; double torquePtgRws[4] = {0, 0, 0, 0}, rwTrqNs[4] = {0, 0, 0, 0};
double torqueRws[4] = {0, 0, 0, 0}, torqueRwsScaled[4] = {0, 0, 0, 0}; double torqueRws[4] = {0, 0, 0, 0}, torqueRwsScaled[4] = {0, 0, 0, 0};
double mgtDpDes[3] = {0, 0, 0}, dipolUnits[3] = {0, 0, 0}; // Desaturation Dipol double mgtDpDes[3] = {0, 0, 0};
switch (submode) { switch (submode) {
case acs::PTG_IDLE: case acs::PTG_IDLE:
@ -395,45 +395,60 @@ void AcsController::performPointingCtrl() {
} }
if (enableAntiStiction) { if (enableAntiStiction) {
bool rwAvailable[4] = {true, true, true, true}; // WHICH INPUT SENSOR SET? ptgCtrl.rwAntistiction(&sensorValues, torqueRwsScaled);
int32_t rwSpeed[4] = {
(sensorValues.rw1Set.currSpeed.value), (sensorValues.rw2Set.currSpeed.value),
(sensorValues.rw3Set.currSpeed.value), (sensorValues.rw4Set.currSpeed.value)};
ptgCtrl.rwAntistiction(rwAvailable, rwSpeed, torqueRwsScaled);
} }
double cmdSpeedRws[4] = {0, 0, 0, 0}; // Should be given to the actuator reaction wheel as input int32_t cmdSpeedRws[4] = {0, 0, 0, 0};
actuatorCmd.cmdSpeedToRws(&(sensorValues.rw1Set.currSpeed.value), actuatorCmd.cmdSpeedToRws(sensorValues.rw1Set.currSpeed.value,
&(sensorValues.rw2Set.currSpeed.value), sensorValues.rw2Set.currSpeed.value,
&(sensorValues.rw3Set.currSpeed.value), sensorValues.rw3Set.currSpeed.value,
&(sensorValues.rw4Set.currSpeed.value), torqueRwsScaled, cmdSpeedRws); sensorValues.rw4Set.currSpeed.value, torqueRwsScaled, cmdSpeedRws);
actuatorCmd.cmdDipolMtq(mgtDpDes, dipolUnits); int16_t cmdDipolMtqs[3] = {0, 0, 0};
actuatorCmd.cmdDipolMtq(mgtDpDes, cmdDipolMtqs);
int16_t cmdDipolUnitsInt[3] = {0, 0, 0};
for (int i = 0; i < 3; ++i) {
cmdDipolUnitsInt[i] = std::round(dipolUnits[i]);
}
int32_t cmdRwSpeedInt[4] = {0, 0, 0, 0};
for (int i = 0; i < 4; ++i) {
cmdRwSpeedInt[i] = std::round(cmdSpeedRws[i]);
}
{ {
PoolReadGuard pg(&actuatorCmdData); PoolReadGuard pg(&actuatorCmdData);
if (pg.getReadResult() == returnvalue::OK) { if (pg.getReadResult() == returnvalue::OK) {
std::memcpy(actuatorCmdData.rwTargetTorque.value, rwTrqNs, 4 * sizeof(double)); std::memcpy(actuatorCmdData.rwTargetTorque.value, rwTrqNs, 4 * sizeof(double));
std::memcpy(actuatorCmdData.rwTargetSpeed.value, cmdRwSpeedInt, 4 * sizeof(int32_t)); std::memcpy(actuatorCmdData.rwTargetSpeed.value, cmdSpeedRws, 4 * sizeof(int32_t));
std::memcpy(actuatorCmdData.mtqTargetDipole.value, cmdDipolUnitsInt, 3 * sizeof(int16_t)); std::memcpy(actuatorCmdData.mtqTargetDipole.value, cmdDipolMtqs, 3 * sizeof(int16_t));
actuatorCmdData.setValidity(true, true); actuatorCmdData.setValidity(true, true);
} }
} }
// {
// PoolReadGuard pg(&dipoleSet); // commandActuators(cmdDipolMtqs[0], cmdDipolMtqs[1], cmdDipolMtqs[2],
// MutexGuard mg(torquer::lazyLock()); // acsParameters.magnetorquesParameter.torqueDuration, cmdSpeedRws[0],
// torquer::NEW_ACTUATION_FLAG = true; // cmdSpeedRws[1], cmdSpeedRws[2], cmdSpeedRws[3],
// dipoleSet.setDipoles(cmdDipolUnitsInt[0], cmdDipolUnitsInt[1], cmdDipolUnitsInt[2], // acsParameters.rwHandlingParameters.rampTime);
// torqueDuration); }
// }
ReturnValue_t AcsController::commandActuators(int16_t xDipole, int16_t yDipole, int16_t zDipole,
uint16_t dipoleTorqueDuration, int32_t rw1Speed,
int32_t rw2Speed, int32_t rw3Speed, int32_t rw4Speed,
uint16_t rampTime) {
{
PoolReadGuard pg(&dipoleSet);
MutexGuard mg(torquer::lazyLock());
torquer::NEW_ACTUATION_FLAG = true;
dipoleSet.setDipoles(xDipole, yDipole, zDipole, dipoleTorqueDuration);
}
{
PoolReadGuard pg(&rw1SpeedSet);
rw1SpeedSet.setRwSpeed(rw1Speed, rampTime);
}
{
PoolReadGuard pg(&rw2SpeedSet);
rw2SpeedSet.setRwSpeed(rw2Speed, rampTime);
}
{
PoolReadGuard pg(&rw3SpeedSet);
rw3SpeedSet.setRwSpeed(rw3Speed, rampTime);
}
{
PoolReadGuard pg(&rw4SpeedSet);
rw4SpeedSet.setRwSpeed(rw4Speed, rampTime);
}
return returnvalue::OK;
} }
ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap, ReturnValue_t AcsController::initializeLocalDataPool(localpool::DataPool &localDataPoolMap,

View File

@ -5,6 +5,7 @@
#include <fsfw/globalfunctions/math/VectorOperations.h> #include <fsfw/globalfunctions/math/VectorOperations.h>
#include <fsfw/parameters/ParameterHelper.h> #include <fsfw/parameters/ParameterHelper.h>
#include <fsfw/parameters/ReceivesParameterMessagesIF.h> #include <fsfw/parameters/ReceivesParameterMessagesIF.h>
#include <mission/devices/devicedefinitions/rwHelpers.h>
#include "acs/ActuatorCmd.h" #include "acs/ActuatorCmd.h"
#include "acs/Guidance.h" #include "acs/Guidance.h"
@ -49,6 +50,7 @@ class AcsController : public ExtendedControllerBase, public ReceivesParameterMes
PtgCtrl ptgCtrl; PtgCtrl ptgCtrl;
uint8_t detumbleCounter; uint8_t detumbleCounter;
uint8_t multipleRwUnavailableCounter;
ParameterHelper parameterHelper; ParameterHelper parameterHelper;
@ -74,11 +76,20 @@ class AcsController : public ExtendedControllerBase, public ReceivesParameterMes
void modeChanged(Mode_t mode, Submode_t submode); void modeChanged(Mode_t mode, Submode_t submode);
void announceMode(bool recursive); void announceMode(bool recursive);
ReturnValue_t commandActuators(int16_t xDipole, int16_t yDipole, int16_t zDipole,
uint16_t dipoleTorqueDuration, int32_t rw1Speed, int32_t rw2Speed,
int32_t rw3Speed, int32_t rw4Speed, uint16_t rampTime);
/* ACS Sensor Values */ /* ACS Sensor Values */
ACS::SensorValues sensorValues; ACS::SensorValues sensorValues;
/* ACS Datasets */ /* ACS Actuation Datasets */
IMTQ::DipoleActuationSet dipoleSet = IMTQ::DipoleActuationSet(objects::IMTQ_HANDLER); IMTQ::DipoleActuationSet dipoleSet = IMTQ::DipoleActuationSet(objects::IMTQ_HANDLER);
rws::RwSpeedActuationSet rw1SpeedSet = rws::RwSpeedActuationSet(objects::RW1);
rws::RwSpeedActuationSet rw2SpeedSet = rws::RwSpeedActuationSet(objects::RW2);
rws::RwSpeedActuationSet rw3SpeedSet = rws::RwSpeedActuationSet(objects::RW3);
rws::RwSpeedActuationSet rw4SpeedSet = rws::RwSpeedActuationSet(objects::RW4);
/* ACS Datasets */
// MGMs // MGMs
acsctrl::MgmDataRaw mgmDataRaw; acsctrl::MgmDataRaw mgmDataRaw;
PoolEntry<float> mgm0VecRaw = PoolEntry<float>(3); PoolEntry<float> mgm0VecRaw = PoolEntry<float>(3);

View File

@ -9,10 +9,10 @@
#include <mission/devices/devicedefinitions/GomspaceDefinitions.h> #include <mission/devices/devicedefinitions/GomspaceDefinitions.h>
#include <mission/devices/devicedefinitions/GyroADIS1650XDefinitions.h> #include <mission/devices/devicedefinitions/GyroADIS1650XDefinitions.h>
#include <mission/devices/devicedefinitions/GyroL3GD20Definitions.h> #include <mission/devices/devicedefinitions/GyroL3GD20Definitions.h>
#include <mission/devices/devicedefinitions/RwDefinitions.h>
#include <mission/devices/devicedefinitions/SyrlinksDefinitions.h> #include <mission/devices/devicedefinitions/SyrlinksDefinitions.h>
#include <mission/devices/devicedefinitions/imtqHandlerDefinitions.h> #include <mission/devices/devicedefinitions/imtqHandlerDefinitions.h>
#include <mission/devices/devicedefinitions/payloadPcduDefinitions.h> #include <mission/devices/devicedefinitions/payloadPcduDefinitions.h>
#include <mission/devices/devicedefinitions/rwHelpers.h>
#include <objects/systemObjectList.h> #include <objects/systemObjectList.h>
ThermalController::ThermalController(object_id_t objectId, HeaterHandler& heater) ThermalController::ThermalController(object_id_t objectId, HeaterHandler& heater)
@ -689,7 +689,7 @@ void ThermalController::copyDevices() {
} }
{ {
lp_var_t<int32_t> tempRw1 = lp_var_t<int32_t>(objects::RW1, RwDefinitions::TEMPERATURE_C); lp_var_t<int32_t> tempRw1 = lp_var_t<int32_t>(objects::RW1, rws::TEMPERATURE_C);
PoolReadGuard pg(&tempRw1, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT); PoolReadGuard pg(&tempRw1, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
if (pg.getReadResult() != returnvalue::OK) { if (pg.getReadResult() != returnvalue::OK) {
sif::warning << "ThermalController: Failed to read reaction wheel 1 temperature" << std::endl; sif::warning << "ThermalController: Failed to read reaction wheel 1 temperature" << std::endl;
@ -702,7 +702,7 @@ void ThermalController::copyDevices() {
} }
{ {
lp_var_t<int32_t> tempRw2 = lp_var_t<int32_t>(objects::RW2, RwDefinitions::TEMPERATURE_C); lp_var_t<int32_t> tempRw2 = lp_var_t<int32_t>(objects::RW2, rws::TEMPERATURE_C);
PoolReadGuard pg(&tempRw2, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT); PoolReadGuard pg(&tempRw2, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
if (pg.getReadResult() != returnvalue::OK) { if (pg.getReadResult() != returnvalue::OK) {
sif::warning << "ThermalController: Failed to read reaction wheel 2 temperature" << std::endl; sif::warning << "ThermalController: Failed to read reaction wheel 2 temperature" << std::endl;
@ -715,7 +715,7 @@ void ThermalController::copyDevices() {
} }
{ {
lp_var_t<int32_t> tempRw3 = lp_var_t<int32_t>(objects::RW3, RwDefinitions::TEMPERATURE_C); lp_var_t<int32_t> tempRw3 = lp_var_t<int32_t>(objects::RW3, rws::TEMPERATURE_C);
PoolReadGuard pg(&tempRw3, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT); PoolReadGuard pg(&tempRw3, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
if (pg.getReadResult() != returnvalue::OK) { if (pg.getReadResult() != returnvalue::OK) {
sif::warning << "ThermalController: Failed to read reaction wheel 3 temperature" << std::endl; sif::warning << "ThermalController: Failed to read reaction wheel 3 temperature" << std::endl;
@ -728,7 +728,7 @@ void ThermalController::copyDevices() {
} }
{ {
lp_var_t<int32_t> tempRw4 = lp_var_t<int32_t>(objects::RW4, RwDefinitions::TEMPERATURE_C); lp_var_t<int32_t> tempRw4 = lp_var_t<int32_t>(objects::RW4, rws::TEMPERATURE_C);
PoolReadGuard pg(&tempRw4, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT); PoolReadGuard pg(&tempRw4, MutexIF::TimeoutType::WAITING, MUTEX_TIMEOUT);
if (pg.getReadResult() != returnvalue::OK) { if (pg.getReadResult() != returnvalue::OK) {
sif::warning << "ThermalController: Failed to read reaction wheel 4 temperature" << std::endl; sif::warning << "ThermalController: Failed to read reaction wheel 4 temperature" << std::endl;

View File

@ -278,6 +278,9 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId,
case 0x4: case 0x4:
parameterWrapper->set(rwHandlingParameters.stictionTorque); parameterWrapper->set(rwHandlingParameters.stictionTorque);
break; break;
case 0x5:
parameterWrapper->set(rwHandlingParameters.rampTime);
break;
default: default:
return INVALID_IDENTIFIER_ID; return INVALID_IDENTIFIER_ID;
} }
@ -291,17 +294,17 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId,
parameterWrapper->set(rwMatrices.pseudoInverse); parameterWrapper->set(rwMatrices.pseudoInverse);
break; break;
case 0x2: case 0x2:
parameterWrapper->set(rwMatrices.without0);
break;
case 0x3:
parameterWrapper->set(rwMatrices.without1); parameterWrapper->set(rwMatrices.without1);
break; break;
case 0x4: case 0x3:
parameterWrapper->set(rwMatrices.without2); parameterWrapper->set(rwMatrices.without2);
break; break;
case 0x5: case 0x4:
parameterWrapper->set(rwMatrices.without3); parameterWrapper->set(rwMatrices.without3);
break; break;
case 0x5:
parameterWrapper->set(rwMatrices.without4);
break;
case 0x6: case 0x6:
parameterWrapper->set(rwMatrices.nullspace); parameterWrapper->set(rwMatrices.nullspace);
break; break;
@ -584,6 +587,9 @@ ReturnValue_t AcsParameters::getParameter(uint8_t domainId, uint8_t parameterId,
case 0x5: case 0x5:
parameterWrapper->set(magnetorquesParameter.DipolMax); parameterWrapper->set(magnetorquesParameter.DipolMax);
break; break;
case 0x6:
parameterWrapper->set(magnetorquesParameter.torqueDuration);
break;
default: default:
return INVALID_IDENTIFIER_ID; return INVALID_IDENTIFIER_ID;
} }

View File

@ -73,9 +73,9 @@ class AcsParameters : public HasParametersIF {
{-0.007534, 1.253879, 0.006812}, {-0.007534, 1.253879, 0.006812},
{-0.037072, 0.006812, 1.313158}}; {-0.037072, 0.006812, 1.313158}};
float mgm02variance[3] = {1, 1, 1}; float mgm02variance[3] = {pow(3.2e-7, 2), pow(3.2e-7, 2), pow(4.1e-7, 2)};
float mgm13variance[3] = {1, 1, 1}; float mgm13variance[3] = {pow(1.5e-8, 2), pow(1.5e-8, 2), pow(1.5e-8, 2)};
float mgm4variance[3] = {1, 1, 1}; float mgm4variance[3] = {pow(1.7e-6, 2), pow(1.7e-6, 2), pow(1.7e-6, 2)};
} mgmHandlingParameters; } mgmHandlingParameters;
struct SusHandlingParameters { struct SusHandlingParameters {
@ -779,19 +779,21 @@ class AcsParameters : public HasParametersIF {
/* var = sqrt(sigma), sigma = RND*sqrt(freq), following values are RND^2 and not var as freq is /* var = sqrt(sigma), sigma = RND*sqrt(freq), following values are RND^2 and not var as freq is
* assumed to be equal for the same class of sensors */ * assumed to be equal for the same class of sensors */
float gyr02variance[3] = {pow(3.0e-3 * sqrt(2), 2), // RND_x = 3.0e-3 deg/s/sqrt(Hz) rms float gyr02variance[3] = {pow(3.0e-3, 2), // RND_x = 3.0e-3 deg/s/sqrt(Hz) rms
pow(3.0e-3 * sqrt(2), 2), // RND_y = 3.0e-3 deg/s/sqrt(Hz) rms pow(3.0e-3, 2), // RND_y = 3.0e-3 deg/s/sqrt(Hz) rms
pow(4.3e-3 * sqrt(2), 2)}; // RND_z = 4.3e-3 deg/s/sqrt(Hz) rms pow(4.3e-3, 2)}; // RND_z = 4.3e-3 deg/s/sqrt(Hz) rms
float gyr13variance[3] = {pow(11e-3, 2), pow(11e-3, 2), pow(11e-3, 2)}; float gyr13variance[3] = {pow(11e-3, 2), pow(11e-3, 2), pow(11e-3, 2)};
uint8_t preferAdis = true; uint8_t preferAdis = true;
} gyrHandlingParameters; } gyrHandlingParameters;
struct RwHandlingParameters { struct RwHandlingParameters {
double inertiaWheel = 0.000028198; double inertiaWheel = 0.000028198;
double maxTrq = 0.0032; // 3.2 [mNm] double maxTrq = 0.0032; // 3.2 [mNm]
double stictionSpeed = 100; // 80; // RPM int32_t stictionSpeed = 100; // RPM
double stictionReleaseSpeed = 120; // RPM int32_t stictionReleaseSpeed = 120; // RPM
double stictionTorque = 0.0006; double stictionTorque = 0.0006;
uint16_t rampTime = 10;
} rwHandlingParameters; } rwHandlingParameters;
struct RwMatrices { struct RwMatrices {
@ -800,13 +802,13 @@ class AcsParameters : public HasParametersIF {
{0.3907, 0.3907, 0.3907, 0.3907}}; {0.3907, 0.3907, 0.3907, 0.3907}};
double pseudoInverse[4][3] = { double pseudoInverse[4][3] = {
{0.5432, 0, 0.6398}, {0, -0.5432, 0.6398}, {-0.5432, 0, 0.6398}, {0, 0.5432, 0.6398}}; {0.5432, 0, 0.6398}, {0, -0.5432, 0.6398}, {-0.5432, 0, 0.6398}, {0, 0.5432, 0.6398}};
double without0[4][3] = {
{0, 0, 0}, {0.5432, -0.5432, 1.2797}, {-1.0864, 0, 0}, {0.5432, 0.5432, 1.2797}};
double without1[4][3] = { double without1[4][3] = {
{0.5432, -0.5432, 1.2797}, {0, 0, 0}, {-0.5432, -0.5432, 1.2797}, {0, 1.0864, 0}}; {0, 0, 0}, {0.5432, -0.5432, 1.2797}, {-1.0864, 0, 0}, {0.5432, 0.5432, 1.2797}};
double without2[4][3] = { double without2[4][3] = {
{1.0864, 0, 0}, {-0.5432, -0.5432, 1.2797}, {0, 0, 0}, {-0.5432, 0.5432, 1.2797}}; {0.5432, -0.5432, 1.2797}, {0, 0, 0}, {-0.5432, -0.5432, 1.2797}, {0, 1.0864, 0}};
double without3[4][3] = { double without3[4][3] = {
{1.0864, 0, 0}, {-0.5432, -0.5432, 1.2797}, {0, 0, 0}, {-0.5432, 0.5432, 1.2797}};
double without4[4][3] = {
{0.5432, 0.5432, 1.2797}, {0, -1.0864, 0}, {-0.5432, 0.5432, 1.2797}, {0, 0, 0}}; {0.5432, 0.5432, 1.2797}, {0, -1.0864, 0}, {-0.5432, 0.5432, 1.2797}, {0, 0, 0}};
double nullspace[4] = {-0.5000, 0.5000, -0.5000, 0.5000}; double nullspace[4] = {-0.5000, 0.5000, -0.5000, 0.5000};
} rwMatrices; } rwMatrices;
@ -910,6 +912,7 @@ class AcsParameters : public HasParametersIF {
double inverseAlignment[3][3] = {{0, -1, 0}, {0, 0, 1}, {-1, 0, 0}}; double inverseAlignment[3][3] = {{0, -1, 0}, {0, 0, 1}, {-1, 0, 0}};
double DipolMax = 0.2; // [Am^2] double DipolMax = 0.2; // [Am^2]
uint16_t torqueDuration = 300; // [ms]
} magnetorquesParameter; } magnetorquesParameter;
struct DetumbleParameter { struct DetumbleParameter {

View File

@ -1,10 +1,3 @@
/*
* ActuatorCmd.cpp
*
* Created on: 4 Aug 2022
* Author: Robin Marquardt
*/
#include "ActuatorCmd.h" #include "ActuatorCmd.h"
#include <fsfw/globalfunctions/constants.h> #include <fsfw/globalfunctions/constants.h>
@ -38,27 +31,33 @@ void ActuatorCmd::scalingTorqueRws(const double *rwTrq, double *rwTrqScaled) {
} }
} }
void ActuatorCmd::cmdSpeedToRws(const int32_t *speedRw0, const int32_t *speedRw1, void ActuatorCmd::cmdSpeedToRws(const int32_t speedRw0, const int32_t speedRw1,
const int32_t *speedRw2, const int32_t *speedRw3, const int32_t speedRw2, const int32_t speedRw3,
const double *rwTorque, double *rwCmdSpeed) { const double *rwTorque, int32_t *rwCmdSpeed) {
using namespace Math; using namespace Math;
// Calculating the commanded speed in RPM for every reaction wheel // Calculating the commanded speed in RPM for every reaction wheel
double speedRws[4] = {(double)*speedRw0, (double)*speedRw1, (double)*speedRw2, (double)*speedRw3}; int32_t speedRws[4] = {speedRw0, speedRw1, speedRw2, speedRw3};
double deltaSpeed[4] = {0, 0, 0, 0}; double deltaSpeed[4] = {0, 0, 0, 0};
double commandTime = acsParameters.onBoardParams.sampleTime, double commandTime = acsParameters.onBoardParams.sampleTime,
inertiaWheel = acsParameters.rwHandlingParameters.inertiaWheel; inertiaWheel = acsParameters.rwHandlingParameters.inertiaWheel;
double radToRpm = 60 / (2 * PI); // factor for conversion to RPM double radToRpm = 60 / (2 * PI); // factor for conversion to RPM
// W_RW = Torque_RW / I_RW * delta t [rad/s] // W_RW = Torque_RW / I_RW * delta t [rad/s]
double factor = commandTime / inertiaWheel * radToRpm; double factor = commandTime / inertiaWheel * radToRpm;
int32_t deltaSpeedInt[4] = {0, 0, 0, 0};
VectorOperations<double>::mulScalar(rwTorque, factor, deltaSpeed, 4); VectorOperations<double>::mulScalar(rwTorque, factor, deltaSpeed, 4);
VectorOperations<double>::add(speedRws, deltaSpeed, rwCmdSpeed, 4); for (int i = 0; i < 4; i++) {
deltaSpeedInt[i] = std::round(deltaSpeed[i]);
}
VectorOperations<int32_t>::add(speedRws, deltaSpeedInt, rwCmdSpeed, 4);
VectorOperations<int32_t>::mulScalar(rwCmdSpeed, 10, rwCmdSpeed, 4);
} }
void ActuatorCmd::cmdDipolMtq(const double *dipolMoment, double *dipolMomentActuator) { void ActuatorCmd::cmdDipolMtq(const double *dipolMoment, int16_t *dipolMomentActuator) {
// Convert to actuator frame // Convert to actuator frame
double dipolMomentActuatorDouble[3] = {0, 0, 0};
MatrixOperations<double>::multiply(*acsParameters.magnetorquesParameter.inverseAlignment, MatrixOperations<double>::multiply(*acsParameters.magnetorquesParameter.inverseAlignment,
dipolMoment, dipolMomentActuator, 3, 3, 1); dipolMoment, dipolMomentActuatorDouble, 3, 3, 1);
// Scaling along largest element if dipol exceeds maximum // Scaling along largest element if dipol exceeds maximum
double maxDipol = acsParameters.magnetorquesParameter.DipolMax; double maxDipol = acsParameters.magnetorquesParameter.DipolMax;
double maxValue = 0; double maxValue = 0;
@ -69,8 +68,12 @@ void ActuatorCmd::cmdDipolMtq(const double *dipolMoment, double *dipolMomentActu
} }
if (maxValue > maxDipol) { if (maxValue > maxDipol) {
double scalingFactor = maxDipol / maxValue; double scalingFactor = maxDipol / maxValue;
VectorOperations<double>::mulScalar(dipolMomentActuator, scalingFactor, dipolMomentActuator, 3); VectorOperations<double>::mulScalar(dipolMomentActuatorDouble, scalingFactor,
dipolMomentActuatorDouble, 3);
} }
// scale dipole from 1 Am^2 to 1e^-4 Am^2 // scale dipole from 1 Am^2 to 1e^-4 Am^2
VectorOperations<double>::mulScalar(dipolMomentActuator, 1e4, dipolMomentActuator, 3); VectorOperations<double>::mulScalar(dipolMomentActuatorDouble, 1e4, dipolMomentActuatorDouble, 3);
for (int i = 0; i < 3; i++) {
dipolMomentActuator[i] = std::round(dipolMomentActuatorDouble[i]);
}
} }

View File

@ -28,8 +28,8 @@ class ActuatorCmd {
* rwCmdSpeed output revolutions per minute for every * rwCmdSpeed output revolutions per minute for every
* reaction wheel * reaction wheel
*/ */
void cmdSpeedToRws(const int32_t *speedRw0, const int32_t *speedRw1, const int32_t *speedRw2, void cmdSpeedToRws(const int32_t speedRw0, const int32_t speedRw1, const int32_t speedRw2,
const int32_t *speedRw3, const double *rwTorque, double *rwCmdSpeed); const int32_t speedRw3, const double *rwTorque, int32_t *rwCmdSpeed);
/* /*
* @brief: cmdDipolMtq() gives the commanded dipol moment for the magnetorques * @brief: cmdDipolMtq() gives the commanded dipol moment for the magnetorques
@ -37,7 +37,7 @@ class ActuatorCmd {
* @param: dipolMoment given dipol moment in spacecraft frame * @param: dipolMoment given dipol moment in spacecraft frame
* dipolMomentActuator resulting dipol moment in actuator reference frame * dipolMomentActuator resulting dipol moment in actuator reference frame
*/ */
void cmdDipolMtq(const double *dipolMoment, double *dipolMomentActuator); void cmdDipolMtq(const double *dipolMoment, int16_t *dipolMomentActuator);
protected: protected:
private: private:

View File

@ -610,104 +610,33 @@ void Guidance::comparePtg(double targetQuat[4], acsctrl::MekfData *mekfData, dou
// under 150 arcsec ?? // under 150 arcsec ??
} }
void Guidance::getDistributionMatrixRw(ACS::SensorValues *sensorValues, double *rwPseudoInv) { ReturnValue_t Guidance::getDistributionMatrixRw(ACS::SensorValues *sensorValues,
if (sensorValues->rw1Set.isValid() && sensorValues->rw2Set.isValid() && double *rwPseudoInv) {
sensorValues->rw3Set.isValid() && sensorValues->rw4Set.isValid()) { bool rw1valid = (sensorValues->rw1Set.state.value && sensorValues->rw1Set.state.isValid());
rwPseudoInv[0] = acsParameters.rwMatrices.pseudoInverse[0][0]; bool rw2valid = (sensorValues->rw2Set.state.value && sensorValues->rw2Set.state.isValid());
rwPseudoInv[1] = acsParameters.rwMatrices.pseudoInverse[0][1]; bool rw3valid = (sensorValues->rw3Set.state.value && sensorValues->rw3Set.state.isValid());
rwPseudoInv[2] = acsParameters.rwMatrices.pseudoInverse[0][2]; bool rw4valid = (sensorValues->rw4Set.state.value && sensorValues->rw4Set.state.isValid());
rwPseudoInv[3] = acsParameters.rwMatrices.pseudoInverse[1][0];
rwPseudoInv[4] = acsParameters.rwMatrices.pseudoInverse[1][1];
rwPseudoInv[5] = acsParameters.rwMatrices.pseudoInverse[1][2];
rwPseudoInv[6] = acsParameters.rwMatrices.pseudoInverse[2][0];
rwPseudoInv[7] = acsParameters.rwMatrices.pseudoInverse[2][1];
rwPseudoInv[8] = acsParameters.rwMatrices.pseudoInverse[2][2];
rwPseudoInv[9] = acsParameters.rwMatrices.pseudoInverse[3][0];
rwPseudoInv[10] = acsParameters.rwMatrices.pseudoInverse[3][1];
rwPseudoInv[11] = acsParameters.rwMatrices.pseudoInverse[3][2];
} if (rw1valid && rw2valid && rw3valid && rw4valid) {
std::memcpy(rwPseudoInv, acsParameters.rwMatrices.pseudoInverse, 12 * sizeof(double));
else if (!(sensorValues->rw1Set.isValid()) && sensorValues->rw2Set.isValid() && return returnvalue::OK;
sensorValues->rw3Set.isValid() && sensorValues->rw4Set.isValid()) { } else if (!rw1valid && rw2valid && rw3valid && rw4valid) {
rwPseudoInv[0] = acsParameters.rwMatrices.without0[0][0]; std::memcpy(rwPseudoInv, acsParameters.rwMatrices.without1, 12 * sizeof(double));
rwPseudoInv[1] = acsParameters.rwMatrices.without0[0][1]; return returnvalue::OK;
rwPseudoInv[2] = acsParameters.rwMatrices.without0[0][2]; } else if (rw1valid && !rw2valid && rw3valid && rw4valid) {
rwPseudoInv[3] = acsParameters.rwMatrices.without0[1][0]; std::memcpy(rwPseudoInv, acsParameters.rwMatrices.without2, 12 * sizeof(double));
rwPseudoInv[4] = acsParameters.rwMatrices.without0[1][1]; return returnvalue::OK;
rwPseudoInv[5] = acsParameters.rwMatrices.without0[1][2]; } else if (rw1valid && rw2valid && !rw3valid && rw4valid) {
rwPseudoInv[6] = acsParameters.rwMatrices.without0[2][0]; std::memcpy(rwPseudoInv, acsParameters.rwMatrices.without3, 12 * sizeof(double));
rwPseudoInv[7] = acsParameters.rwMatrices.without0[2][1]; return returnvalue::OK;
rwPseudoInv[8] = acsParameters.rwMatrices.without0[2][2]; } else if (rw1valid && rw2valid && rw3valid && !rw4valid) {
rwPseudoInv[9] = acsParameters.rwMatrices.without0[3][0]; std::memcpy(rwPseudoInv, acsParameters.rwMatrices.without4, 12 * sizeof(double));
rwPseudoInv[10] = acsParameters.rwMatrices.without0[3][1]; return returnvalue::OK;
rwPseudoInv[11] = acsParameters.rwMatrices.without0[3][2]; } else {
}
else if ((sensorValues->rw1Set.isValid()) && !(sensorValues->rw2Set.isValid()) &&
sensorValues->rw3Set.isValid() && sensorValues->rw4Set.isValid()) {
rwPseudoInv[0] = acsParameters.rwMatrices.without1[0][0];
rwPseudoInv[1] = acsParameters.rwMatrices.without1[0][1];
rwPseudoInv[2] = acsParameters.rwMatrices.without1[0][2];
rwPseudoInv[3] = acsParameters.rwMatrices.without1[1][0];
rwPseudoInv[4] = acsParameters.rwMatrices.without1[1][1];
rwPseudoInv[5] = acsParameters.rwMatrices.without1[1][2];
rwPseudoInv[6] = acsParameters.rwMatrices.without1[2][0];
rwPseudoInv[7] = acsParameters.rwMatrices.without1[2][1];
rwPseudoInv[8] = acsParameters.rwMatrices.without1[2][2];
rwPseudoInv[9] = acsParameters.rwMatrices.without1[3][0];
rwPseudoInv[10] = acsParameters.rwMatrices.without1[3][1];
rwPseudoInv[11] = acsParameters.rwMatrices.without1[3][2];
}
else if ((sensorValues->rw1Set.isValid()) && (sensorValues->rw2Set.isValid()) &&
!(sensorValues->rw3Set.isValid()) && sensorValues->rw4Set.isValid()) {
rwPseudoInv[0] = acsParameters.rwMatrices.without2[0][0];
rwPseudoInv[1] = acsParameters.rwMatrices.without2[0][1];
rwPseudoInv[2] = acsParameters.rwMatrices.without2[0][2];
rwPseudoInv[3] = acsParameters.rwMatrices.without2[1][0];
rwPseudoInv[4] = acsParameters.rwMatrices.without2[1][1];
rwPseudoInv[5] = acsParameters.rwMatrices.without2[1][2];
rwPseudoInv[6] = acsParameters.rwMatrices.without2[2][0];
rwPseudoInv[7] = acsParameters.rwMatrices.without2[2][1];
rwPseudoInv[8] = acsParameters.rwMatrices.without2[2][2];
rwPseudoInv[9] = acsParameters.rwMatrices.without2[3][0];
rwPseudoInv[10] = acsParameters.rwMatrices.without2[3][1];
rwPseudoInv[11] = acsParameters.rwMatrices.without2[3][2];
}
else if ((sensorValues->rw1Set.isValid()) && (sensorValues->rw2Set.isValid()) &&
(sensorValues->rw3Set.isValid()) && !(sensorValues->rw4Set.isValid())) {
rwPseudoInv[0] = acsParameters.rwMatrices.without3[0][0];
rwPseudoInv[1] = acsParameters.rwMatrices.without3[0][1];
rwPseudoInv[2] = acsParameters.rwMatrices.without3[0][2];
rwPseudoInv[3] = acsParameters.rwMatrices.without3[1][0];
rwPseudoInv[4] = acsParameters.rwMatrices.without3[1][1];
rwPseudoInv[5] = acsParameters.rwMatrices.without3[1][2];
rwPseudoInv[6] = acsParameters.rwMatrices.without3[2][0];
rwPseudoInv[7] = acsParameters.rwMatrices.without3[2][1];
rwPseudoInv[8] = acsParameters.rwMatrices.without3[2][2];
rwPseudoInv[9] = acsParameters.rwMatrices.without3[3][0];
rwPseudoInv[10] = acsParameters.rwMatrices.without3[3][1];
rwPseudoInv[11] = acsParameters.rwMatrices.without3[3][2];
}
else {
// @note: This one takes the normal pseudoInverse of all four raction wheels valid. // @note: This one takes the normal pseudoInverse of all four raction wheels valid.
// Does not make sense, but is implemented that way in MATLAB ?! // Does not make sense, but is implemented that way in MATLAB ?!
// Thought: It does not really play a role, because in case there are more then one // Thought: It does not really play a role, because in case there are more then one
// reaction wheel invalid the pointing control is destined to fail. // reaction wheel invalid the pointing control is destined to fail.
rwPseudoInv[0] = acsParameters.rwMatrices.pseudoInverse[0][0]; return returnvalue::FAILED;
rwPseudoInv[1] = acsParameters.rwMatrices.pseudoInverse[0][1];
rwPseudoInv[2] = acsParameters.rwMatrices.pseudoInverse[0][2];
rwPseudoInv[3] = acsParameters.rwMatrices.pseudoInverse[1][0];
rwPseudoInv[4] = acsParameters.rwMatrices.pseudoInverse[1][1];
rwPseudoInv[5] = acsParameters.rwMatrices.pseudoInverse[1][2];
rwPseudoInv[6] = acsParameters.rwMatrices.pseudoInverse[2][0];
rwPseudoInv[7] = acsParameters.rwMatrices.pseudoInverse[2][1];
rwPseudoInv[8] = acsParameters.rwMatrices.pseudoInverse[2][2];
rwPseudoInv[9] = acsParameters.rwMatrices.pseudoInverse[3][0];
rwPseudoInv[10] = acsParameters.rwMatrices.pseudoInverse[3][1];
rwPseudoInv[11] = acsParameters.rwMatrices.pseudoInverse[3][2];
} }
} }

View File

@ -67,7 +67,7 @@ class Guidance {
// @note: will give back the pseudoinverse matrix for the reaction wheel depending on the valid // @note: will give back the pseudoinverse matrix for the reaction wheel depending on the valid
// reation wheel maybe can be done in "commanding.h" // reation wheel maybe can be done in "commanding.h"
void getDistributionMatrixRw(ACS::SensorValues *sensorValues, double *rwPseudoInv); ReturnValue_t getDistributionMatrixRw(ACS::SensorValues *sensorValues, double *rwPseudoInv);
private: private:
AcsParameters acsParameters; AcsParameters acsParameters;

View File

@ -20,6 +20,7 @@ Igrf13Model::~Igrf13Model() {}
void Igrf13Model::magFieldComp(const double longitude, const double gcLatitude, void Igrf13Model::magFieldComp(const double longitude, const double gcLatitude,
const double altitude, timeval timeOfMagMeasurement, const double altitude, timeval timeOfMagMeasurement,
double* magFieldModelInertial) { double* magFieldModelInertial) {
double magFieldModel[3] = {0, 0, 0};
double phi = longitude, theta = gcLatitude; // geocentric double phi = longitude, theta = gcLatitude; // geocentric
/* Here is the co-latitude needed*/ /* Here is the co-latitude needed*/
theta -= 90 * PI / 180; theta -= 90 * PI / 180;
@ -100,12 +101,8 @@ void Igrf13Model::magFieldComp(const double longitude, const double gcLatitude,
magFieldModelInertial[2] = magFieldModelInertial[2] =
magFieldModel[0] * sin(gcLatitude) - magFieldModel[1] * cos(gcLatitude); magFieldModel[0] * sin(gcLatitude) - magFieldModel[1] * cos(gcLatitude);
double normVecMagFieldInert[3] = {0, 0, 0}; // convert nT to uT
VectorOperations<double>::normalize(magFieldModelInertial, normVecMagFieldInert, 3); VectorOperations<double>::mulScalar(magFieldModelInertial, 1e-3, magFieldModelInertial, 3);
magFieldModel[0] = 0;
magFieldModel[1] = 0;
magFieldModel[2] = 0;
} }
void Igrf13Model::updateCoeffGH(timeval timeOfMagMeasurement) { void Igrf13Model::updateCoeffGH(timeval timeOfMagMeasurement) {

View File

@ -47,7 +47,6 @@ class Igrf13Model /*:public HasParametersIF*/ {
// Coefficient wary over year, could be updated sometimes. // Coefficient wary over year, could be updated sometimes.
void updateCoeffGH(timeval timeOfMagMeasurement); // Secular variation (SV) void updateCoeffGH(timeval timeOfMagMeasurement); // Secular variation (SV)
double magFieldModel[3];
void schmidtNormalization(); void schmidtNormalization();
private: private:

View File

@ -1,13 +1,14 @@
#ifndef SENSORVALUES_H_ #ifndef SENSORVALUES_H_
#define SENSORVALUES_H_ #define SENSORVALUES_H_
#include <mission/devices/devicedefinitions/rwHelpers.h>
#include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h" #include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h"
#include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h" #include "fsfw_hal/devicehandlers/MgmLIS3MDLHandler.h"
#include "fsfw_hal/devicehandlers/MgmRM3100Handler.h" #include "fsfw_hal/devicehandlers/MgmRM3100Handler.h"
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h" #include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
#include "mission/devices/devicedefinitions/GPSDefinitions.h" #include "mission/devices/devicedefinitions/GPSDefinitions.h"
#include "mission/devices/devicedefinitions/GyroADIS1650XDefinitions.h" #include "mission/devices/devicedefinitions/GyroADIS1650XDefinitions.h"
#include "mission/devices/devicedefinitions/RwDefinitions.h"
#include "mission/devices/devicedefinitions/SusDefinitions.h" #include "mission/devices/devicedefinitions/SusDefinitions.h"
#include "mission/devices/devicedefinitions/imtqHandlerDefinitions.h" #include "mission/devices/devicedefinitions/imtqHandlerDefinitions.h"
@ -62,10 +63,10 @@ class SensorValues {
// bool mgt0valid; // bool mgt0valid;
RwDefinitions::StatusSet rw1Set = RwDefinitions::StatusSet(objects::RW1); rws::StatusSet rw1Set = rws::StatusSet(objects::RW1);
RwDefinitions::StatusSet rw2Set = RwDefinitions::StatusSet(objects::RW2); rws::StatusSet rw2Set = rws::StatusSet(objects::RW2);
RwDefinitions::StatusSet rw3Set = RwDefinitions::StatusSet(objects::RW3); rws::StatusSet rw3Set = rws::StatusSet(objects::RW3);
RwDefinitions::StatusSet rw4Set = RwDefinitions::StatusSet(objects::RW4); rws::StatusSet rw4Set = rws::StatusSet(objects::RW4);
}; };
} /* namespace ACS */ } /* namespace ACS */

View File

@ -161,8 +161,14 @@ void PtgCtrl::ptgNullspace(AcsParameters::PointingLawParameters *pointingLawPara
VectorOperations<double>::mulScalar(rwTrqNs, -1, rwTrqNs, 4); VectorOperations<double>::mulScalar(rwTrqNs, -1, rwTrqNs, 4);
} }
void PtgCtrl::rwAntistiction(const bool *rwAvailable, const int32_t *omegaRw, void PtgCtrl::rwAntistiction(ACS::SensorValues *sensorValues, double *torqueCommand) {
double *torqueCommand) { bool rwAvailable[4] = {
(sensorValues->rw1Set.state.value && sensorValues->rw1Set.state.isValid()),
(sensorValues->rw2Set.state.value && sensorValues->rw2Set.state.isValid()),
(sensorValues->rw3Set.state.value && sensorValues->rw3Set.state.isValid()),
(sensorValues->rw4Set.state.value && sensorValues->rw4Set.state.isValid())};
int32_t omegaRw[4] = {sensorValues->rw1Set.currSpeed.value, sensorValues->rw2Set.currSpeed.value,
sensorValues->rw3Set.currSpeed.value, sensorValues->rw4Set.currSpeed.value};
for (uint8_t i = 0; i < 4; i++) { for (uint8_t i = 0; i < 4; i++) {
if (rwAvailable[i]) { if (rwAvailable[i]) {
if (torqueMemory[i] != 0) { if (torqueMemory[i] != 0) {

View File

@ -54,11 +54,10 @@ class PtgCtrl {
const int32_t *speedRw3, double *rwTrqNs); const int32_t *speedRw3, double *rwTrqNs);
/* @brief: Commands the stiction torque in case wheel speed is to low /* @brief: Commands the stiction torque in case wheel speed is to low
* @param: rwAvailable Boolean Flag for all reaction wheels * @param: sensorValues class containing all RW related values
* omegaRw current wheel speed of reaction wheels
* torqueCommand modified torque after antistiction * torqueCommand modified torque after antistiction
*/ */
void rwAntistiction(const bool *rwAvailable, const int32_t *omegaRw, double *torqueCommand); void rwAntistiction(ACS::SensorValues *sensorValues, double *torqueCommand);
private: private:
AcsParameters::RwHandlingParameters *rwHandlingParameters; AcsParameters::RwHandlingParameters *rwHandlingParameters;

View File

@ -183,18 +183,20 @@ ReturnValue_t ImtqHandler::buildCommandFromCommand(DeviceCommandId_t deviceComma
return DeviceHandlerIF::INVALID_COMMAND_PARAMETER; return DeviceHandlerIF::INVALID_COMMAND_PARAMETER;
} }
ReturnValue_t result; ReturnValue_t result;
// Commands override anything which was set in the software {
if (commandData != nullptr) {
dipoleSet.setValidityBufferGeneration(false);
result =
dipoleSet.deSerialize(&commandData, &commandDataLen, SerializeIF::Endianness::NETWORK);
dipoleSet.setValidityBufferGeneration(true);
if (result != returnvalue::OK) {
return result;
}
} else {
// Read set dipole values from local pool // Read set dipole values from local pool
PoolReadGuard pg(&dipoleSet); PoolReadGuard pg(&dipoleSet);
// Commands override anything which was set in the software
if (commandData != nullptr) {
dipoleSet.setValidityBufferGeneration(false);
result = dipoleSet.deSerialize(&commandData, &commandDataLen,
SerializeIF::Endianness::NETWORK);
dipoleSet.setValidityBufferGeneration(true);
if (result != returnvalue::OK) {
return result;
}
}
} }
if (ACTUATION_WIRETAPPING) { if (ACTUATION_WIRETAPPING) {
sif::debug << "Actuating IMTQ with parameters x = " << dipoleSet.xDipole.value sif::debug << "Actuating IMTQ with parameters x = " << dipoleSet.xDipole.value

View File

@ -2,18 +2,21 @@
#include <fsfw/datapool/PoolReadGuard.h> #include <fsfw/datapool/PoolReadGuard.h>
#include <fsfw/globalfunctions/CRC.h> #include <fsfw/globalfunctions/CRC.h>
#include <fsfw/globalfunctions/arrayprinter.h>
#include <fsfw_hal/common/gpio/GpioIF.h> #include <fsfw_hal/common/gpio/GpioIF.h>
#include "OBSWConfig.h" #include "OBSWConfig.h"
RwHandler::RwHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie, RwHandler::RwHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie,
GpioIF* gpioComIF, gpioId_t enableGpio) GpioIF* gpioComIF, gpioId_t enableGpio, uint8_t rwIdx)
: DeviceHandlerBase(objectId, comIF, comCookie), : DeviceHandlerBase(objectId, comIF, comCookie),
gpioComIF(gpioComIF), gpioComIF(gpioComIF),
enableGpio(enableGpio), enableGpio(enableGpio),
statusSet(this), statusSet(this),
lastResetStatusSet(this), lastResetStatusSet(this),
tmDataset(this) { tmDataset(this),
rwSpeedActuationSet(*this),
rwIdx(rwIdx) {
if (comCookie == nullptr) { if (comCookie == nullptr) {
sif::error << "RwHandler: Invalid com cookie" << std::endl; sif::error << "RwHandler: Invalid com cookie" << std::endl;
} }
@ -25,11 +28,12 @@ RwHandler::RwHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCooki
RwHandler::~RwHandler() {} RwHandler::~RwHandler() {}
void RwHandler::doStartUp() { void RwHandler::doStartUp() {
internalState = InternalState::GET_RESET_STATUS; internalState = InternalState::DEFAULT;
if (gpioComIF->pullHigh(enableGpio) != returnvalue::OK) { if (gpioComIF->pullHigh(enableGpio) != returnvalue::OK) {
sif::debug << "RwHandler::doStartUp: Failed to pull enable gpio to high"; sif::debug << "RwHandler::doStartUp: Failed to pull enable gpio to high";
} }
updatePeriodicReply(true, rws::REPLY_ID);
setMode(_MODE_TO_ON); setMode(_MODE_TO_ON);
} }
@ -37,28 +41,18 @@ void RwHandler::doShutDown() {
if (gpioComIF->pullLow(enableGpio) != returnvalue::OK) { if (gpioComIF->pullLow(enableGpio) != returnvalue::OK) {
sif::debug << "RwHandler::doStartUp: Failed to pull enable gpio to low"; sif::debug << "RwHandler::doStartUp: Failed to pull enable gpio to low";
} }
setMode(_MODE_POWER_DOWN); internalState = InternalState::DEFAULT;
updatePeriodicReply(false, rws::REPLY_ID);
// The power switch is handled by the assembly, so we can go off here directly.
setMode(MODE_OFF);
} }
ReturnValue_t RwHandler::buildNormalDeviceCommand(DeviceCommandId_t* id) { ReturnValue_t RwHandler::buildNormalDeviceCommand(DeviceCommandId_t* id) {
switch (internalState) { switch (internalState) {
case InternalState::GET_RESET_STATUS: case InternalState::DEFAULT: {
*id = RwDefinitions::GET_LAST_RESET_STATUS; *id = rws::REQUEST_ID;
internalState = InternalState::READ_TEMPERATURE;
break;
case InternalState::READ_TEMPERATURE:
*id = RwDefinitions::GET_TEMPERATURE;
internalState = InternalState::GET_RW_SATUS;
break;
case InternalState::GET_RW_SATUS:
*id = RwDefinitions::GET_RW_STATUS;
internalState = InternalState::GET_RESET_STATUS;
break;
case InternalState::CLEAR_RESET_STATUS:
*id = RwDefinitions::CLEAR_LAST_RESET_STATUS;
/** After reset status is cleared, reset status will be polled again for verification */
internalState = InternalState::GET_RESET_STATUS;
break; break;
}
default: default:
sif::debug << "RwHandler::buildNormalDeviceCommand: Invalid internal step" << std::endl; sif::debug << "RwHandler::buildNormalDeviceCommand: Invalid internal step" << std::endl;
break; break;
@ -76,45 +70,65 @@ ReturnValue_t RwHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand
ReturnValue_t result = returnvalue::OK; ReturnValue_t result = returnvalue::OK;
switch (deviceCommand) { switch (deviceCommand) {
case (RwDefinitions::RESET_MCU): { case (rws::SET_SPEED):
prepareSimpleCommand(deviceCommand); case (rws::REQUEST_ID): {
return returnvalue::OK; if (commandData != nullptr && commandDataLen != 6) {
}
case (RwDefinitions::GET_LAST_RESET_STATUS): {
prepareSimpleCommand(deviceCommand);
return returnvalue::OK;
}
case (RwDefinitions::CLEAR_LAST_RESET_STATUS): {
prepareSimpleCommand(deviceCommand);
return returnvalue::OK;
}
case (RwDefinitions::GET_RW_STATUS): {
prepareSimpleCommand(deviceCommand);
return returnvalue::OK;
}
case (RwDefinitions::INIT_RW_CONTROLLER): {
prepareSimpleCommand(deviceCommand);
return returnvalue::OK;
}
case (RwDefinitions::SET_SPEED): {
if (commandDataLen != 6) {
sif::error << "RwHandler::buildCommandFromCommand: Received set speed command with" sif::error << "RwHandler::buildCommandFromCommand: Received set speed command with"
<< " invalid length" << std::endl; << " invalid length" << std::endl;
return SET_SPEED_COMMAND_INVALID_LENGTH; return SET_SPEED_COMMAND_INVALID_LENGTH;
} }
result = checkSpeedAndRampTime(commandData, commandDataLen);
{
PoolReadGuard pg(&rwSpeedActuationSet);
// Commands override anything which was set in the software
if (commandData != nullptr) {
rwSpeedActuationSet.setValidityBufferGeneration(false);
result = rwSpeedActuationSet.deSerialize(&commandData, &commandDataLen,
SerializeIF::Endianness::NETWORK);
rwSpeedActuationSet.setValidityBufferGeneration(true);
if (result != returnvalue::OK) {
return result;
}
}
}
if (ACTUATION_WIRETAPPING) {
int32_t speed = 0;
uint16_t rampTime = 0;
rwSpeedActuationSet.getRwSpeed(speed, rampTime);
sif::debug << "Actuating RW " << static_cast<int>(rwIdx) << " with speed = " << speed
<< " and rampTime = " << rampTime << std::endl;
}
result = checkSpeedAndRampTime();
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
return result; return result;
} }
prepareSetSpeedCmd(commandData, commandDataLen); // set speed flag.
return result; commandBuffer[0] = true;
} rawPacketLen = 1;
case (RwDefinitions::GET_TEMPERATURE): { uint8_t* currentCmdBuf = commandBuffer + 1;
prepareSimpleCommand(deviceCommand); rwSpeedActuationSet.serialize(&currentCmdBuf, &rawPacketLen, sizeof(commandBuffer),
SerializeIF::Endianness::MACHINE);
commandBuffer[rawPacketLen++] = static_cast<uint8_t>(rws::SpecialRwRequest::REQUEST_NONE);
rawPacket = commandBuffer;
return returnvalue::OK; return returnvalue::OK;
} }
case (RwDefinitions::GET_TM): { case (rws::RESET_MCU): {
prepareSimpleCommand(deviceCommand); commandBuffer[0] = false;
commandBuffer[7] = static_cast<uint8_t>(rws::SpecialRwRequest::RESET_MCU);
internalState = InternalState::RESET_MCU;
return returnvalue::OK;
}
case (rws::INIT_RW_CONTROLLER): {
commandBuffer[0] = false;
commandBuffer[7] = static_cast<uint8_t>(rws::SpecialRwRequest::INIT_RW_CONTROLLER);
internalState = InternalState::INIT_RW_CONTROLLER;
return returnvalue::OK;
}
case (rws::GET_TM): {
commandBuffer[0] = false;
commandBuffer[7] = static_cast<uint8_t>(rws::SpecialRwRequest::GET_TM);
internalState = InternalState::GET_TM;
return returnvalue::OK; return returnvalue::OK;
} }
default: default:
@ -124,159 +138,161 @@ ReturnValue_t RwHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand
} }
void RwHandler::fillCommandAndReplyMap() { void RwHandler::fillCommandAndReplyMap() {
this->insertInCommandMap(RwDefinitions::RESET_MCU); insertInCommandMap(rws::REQUEST_ID);
this->insertInCommandAndReplyMap(RwDefinitions::GET_LAST_RESET_STATUS, 1, &lastResetStatusSet, insertInReplyMap(rws::REPLY_ID, 5, nullptr, 0, true);
RwDefinitions::SIZE_GET_RESET_STATUS);
this->insertInCommandAndReplyMap(RwDefinitions::CLEAR_LAST_RESET_STATUS, 1, nullptr, insertInCommandMap(rws::RESET_MCU);
RwDefinitions::SIZE_CLEAR_RESET_STATUS); insertInCommandMap(rws::SET_SPEED);
this->insertInCommandAndReplyMap(RwDefinitions::GET_RW_STATUS, 1, &statusSet, insertInCommandAndReplyMap(rws::INIT_RW_CONTROLLER, 5, nullptr, 0, false, true, rws::REPLY_ID);
RwDefinitions::SIZE_GET_RW_STATUS); insertInCommandAndReplyMap(rws::GET_TM, 5, nullptr, 0, false, true, rws::REPLY_ID);
this->insertInCommandAndReplyMap(RwDefinitions::INIT_RW_CONTROLLER, 1, nullptr,
RwDefinitions::SIZE_INIT_RW);
this->insertInCommandAndReplyMap(RwDefinitions::GET_TEMPERATURE, 1, nullptr,
RwDefinitions::SIZE_GET_TEMPERATURE_REPLY);
this->insertInCommandAndReplyMap(RwDefinitions::SET_SPEED, 1, nullptr,
RwDefinitions::SIZE_SET_SPEED_REPLY);
this->insertInCommandAndReplyMap(RwDefinitions::GET_TM, 1, &tmDataset,
RwDefinitions::SIZE_GET_TELEMETRY_REPLY);
} }
ReturnValue_t RwHandler::scanForReply(const uint8_t* start, size_t remainingSize, ReturnValue_t RwHandler::scanForReply(const uint8_t* start, size_t remainingSize,
DeviceCommandId_t* foundId, size_t* foundLen) { DeviceCommandId_t* foundId, size_t* foundLen) {
uint8_t replyByte = *start; if (getMode() == _MODE_WAIT_OFF or getMode() == _MODE_WAIT_ON) {
switch (replyByte) { return IGNORE_FULL_PACKET;
case (RwDefinitions::GET_LAST_RESET_STATUS): { }
*foundLen = RwDefinitions::SIZE_GET_RESET_STATUS; if (remainingSize > 0) {
*foundId = RwDefinitions::GET_LAST_RESET_STATUS; *foundLen = remainingSize;
break; *foundId = rws::REPLY_ID;
}
case (RwDefinitions::CLEAR_LAST_RESET_STATUS): {
*foundLen = RwDefinitions::SIZE_CLEAR_RESET_STATUS;
*foundId = RwDefinitions::CLEAR_LAST_RESET_STATUS;
break;
}
case (RwDefinitions::GET_RW_STATUS): {
*foundLen = RwDefinitions::SIZE_GET_RW_STATUS;
*foundId = RwDefinitions::GET_RW_STATUS;
break;
}
case (RwDefinitions::INIT_RW_CONTROLLER): {
*foundLen = RwDefinitions::SIZE_INIT_RW;
*foundId = RwDefinitions::INIT_RW_CONTROLLER;
break;
}
case (RwDefinitions::SET_SPEED): {
*foundLen = RwDefinitions::SIZE_SET_SPEED_REPLY;
*foundId = RwDefinitions::SET_SPEED;
break;
}
case (RwDefinitions::GET_TEMPERATURE): {
*foundLen = RwDefinitions::SIZE_GET_TEMPERATURE_REPLY;
*foundId = RwDefinitions::GET_TEMPERATURE;
break;
}
case (RwDefinitions::GET_TM): {
*foundLen = RwDefinitions::SIZE_GET_TELEMETRY_REPLY;
*foundId = RwDefinitions::GET_TM;
break;
}
default: {
sif::warning << "RwHandler::scanForReply: Reply contains invalid command code" << std::endl;
*foundLen = remainingSize;
return returnvalue::FAILED;
}
} }
sizeOfReply = *foundLen;
return returnvalue::OK; return returnvalue::OK;
} }
ReturnValue_t RwHandler::interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) { ReturnValue_t RwHandler::interpretDeviceReply(DeviceCommandId_t id, const uint8_t* packet) {
/** Check result code */ RwReplies replies(packet);
if (*(packet + 1) == RwDefinitions::STATE_ERROR) { ReturnValue_t result = returnvalue::OK;
sif::error << "RwHandler::interpretDeviceReply: Command execution failed. Command id: " << id ReturnValue_t status;
<< std::endl; auto checkPacket = [&](DeviceCommandId_t id, const uint8_t* packetPtr) {
return EXECUTION_FAILED; // This is just the packet length of the frame from the RW. The actual
} // data is one more flag byte to show whether the value was read at least once.
auto packetLen = rws::idToPacketLen(id);
/** Received in little endian byte order */ // arrayprinter::print(packetPtr, packetLen);
uint16_t replyCrc = *(packet + sizeOfReply - 1) << 8 | *(packet + sizeOfReply - 2); uint16_t replyCrc;
size_t dummy = 0;
if (CRC::crc16ccitt(packet, sizeOfReply - 2, 0xFFFF) != replyCrc) { SerializeAdapter::deSerialize(&replyCrc, packetPtr + packetLen - 2, &dummy,
sif::error << "RwHandler::interpretDeviceReply: cRC error" << std::endl; SerializeIF::Endianness::LITTLE);
return CRC_ERROR; if (CRC::crc16ccitt(packetPtr, packetLen - 2) != replyCrc) {
} sif::error << "RwHandler::interpretDeviceReply: CRC error for ID " << id << std::endl;
return CRC_ERROR;
switch (id) {
case (RwDefinitions::GET_LAST_RESET_STATUS): {
handleResetStatusReply(packet);
break;
} }
case (RwDefinitions::GET_RW_STATUS): { if (packetPtr[1] == rws::STATE_ERROR) {
handleGetRwStatusReply(packet); sif::error << "RwHandler::interpretDeviceReply: Command execution failed. Command id: " << id
break; << std::endl;
result = EXECUTION_FAILED;
} }
case (RwDefinitions::CLEAR_LAST_RESET_STATUS): return returnvalue::OK;
case (RwDefinitions::INIT_RW_CONTROLLER): };
case (RwDefinitions::SET_SPEED): if (replies.wasSetSpeedReplyRead()) {
// no reply data expected status = checkPacket(rws::DeviceCommandId::SET_SPEED, replies.getSetSpeedReply());
break; if (status != returnvalue::OK) {
case (RwDefinitions::GET_TEMPERATURE): { result = status;
handleTemperatureReply(packet);
break;
}
case (RwDefinitions::GET_TM): {
handleGetTelemetryReply(packet);
break;
}
default: {
sif::debug << "RwHandler::interpretDeviceReply: Unknown device reply id" << std::endl;
return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY;
} }
} }
return returnvalue::OK; if (replies.wasRwStatusRead()) {
status = checkPacket(rws::DeviceCommandId::GET_RW_STATUS, replies.getRwStatusReply());
if (status == returnvalue::OK) {
handleGetRwStatusReply(replies.getRwStatusReply());
} else {
result = status;
}
}
if (replies.wasGetLastStatusReplyRead()) {
status = checkPacket(rws::DeviceCommandId::GET_LAST_RESET_STATUS,
replies.getGetLastResetStatusReply());
if (status == returnvalue::OK) {
handleResetStatusReply(replies.getGetLastResetStatusReply());
} else {
result = status;
}
}
if (replies.wasClearLastRsetStatusReplyRead()) {
status = checkPacket(rws::DeviceCommandId::CLEAR_LAST_RESET_STATUS,
replies.getClearLastResetStatusReply());
if (status != returnvalue::OK) {
result = status;
}
}
if (replies.wasReadTemperatureReplySet()) {
status = checkPacket(rws::DeviceCommandId::GET_TEMPERATURE, replies.getReadTemperatureReply());
if (status == returnvalue::OK) {
handleTemperatureReply(replies.getReadTemperatureReply());
} else {
result = status;
}
}
if (internalState == InternalState::GET_TM) {
if (replies.wasHkDataReplyRead()) {
status = checkPacket(rws::DeviceCommandId::GET_TM, replies.getHkDataReply());
if (status == returnvalue::OK) {
handleGetTelemetryReply(replies.getHkDataReply());
} else {
result = status;
}
internalState = InternalState::DEFAULT;
}
}
if (internalState == InternalState::INIT_RW_CONTROLLER) {
if (replies.wasInitRwControllerReplyRead()) {
status =
checkPacket(rws::DeviceCommandId::INIT_RW_CONTROLLER, replies.getInitRwControllerReply());
if (status != returnvalue::OK) {
result = status;
}
internalState = InternalState::DEFAULT;
}
}
if (internalState == InternalState::RESET_MCU) {
internalState = InternalState::DEFAULT;
}
return result;
} }
uint32_t RwHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 5000; } uint32_t RwHandler::getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) { return 5000; }
ReturnValue_t RwHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, ReturnValue_t RwHandler::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
LocalDataPoolManager& poolManager) { LocalDataPoolManager& poolManager) {
localDataPoolMap.emplace(RwDefinitions::TEMPERATURE_C, new PoolEntry<int32_t>({0})); localDataPoolMap.emplace(rws::RW_SPEED, &rwSpeed);
localDataPoolMap.emplace(rws::RAMP_TIME, &rampTime);
localDataPoolMap.emplace(RwDefinitions::CURR_SPEED, new PoolEntry<int32_t>({0})); localDataPoolMap.emplace(rws::TEMPERATURE_C, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::REFERENCE_SPEED, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::STATE, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::CLC_MODE, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::LAST_RESET_STATUS, new PoolEntry<uint8_t>({0})); localDataPoolMap.emplace(rws::CURR_SPEED, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::CURRRENT_RESET_STATUS, new PoolEntry<uint8_t>({0})); localDataPoolMap.emplace(rws::REFERENCE_SPEED, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(rws::STATE, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(rws::CLC_MODE, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::TM_LAST_RESET_STATUS, new PoolEntry<uint8_t>({0})); localDataPoolMap.emplace(rws::LAST_RESET_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::TM_MCU_TEMPERATURE, new PoolEntry<int32_t>({0})); localDataPoolMap.emplace(rws::CURRRENT_RESET_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::PRESSURE_SENSOR_TEMPERATURE, new PoolEntry<float>({0}));
localDataPoolMap.emplace(RwDefinitions::PRESSURE, new PoolEntry<float>({0})); localDataPoolMap.emplace(rws::TM_LAST_RESET_STATUS, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::TM_RW_STATE, new PoolEntry<uint8_t>({0})); localDataPoolMap.emplace(rws::TM_MCU_TEMPERATURE, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::TM_CLC_MODE, new PoolEntry<uint8_t>({0})); localDataPoolMap.emplace(rws::PRESSURE_SENSOR_TEMPERATURE, new PoolEntry<float>({0}));
localDataPoolMap.emplace(RwDefinitions::TM_RW_CURR_SPEED, new PoolEntry<int32_t>({0})); localDataPoolMap.emplace(rws::PRESSURE, new PoolEntry<float>({0}));
localDataPoolMap.emplace(RwDefinitions::TM_RW_REF_SPEED, new PoolEntry<int32_t>({0})); localDataPoolMap.emplace(rws::TM_RW_STATE, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::INVALID_CRC_PACKETS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::TM_CLC_MODE, new PoolEntry<uint8_t>({0}));
localDataPoolMap.emplace(RwDefinitions::INVALID_LEN_PACKETS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::TM_RW_CURR_SPEED, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::INVALID_CMD_PACKETS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::TM_RW_REF_SPEED, new PoolEntry<int32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::EXECUTED_REPLIES, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::INVALID_CRC_PACKETS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::COMMAND_REPLIES, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::INVALID_LEN_PACKETS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_BYTES_WRITTEN, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::INVALID_CMD_PACKETS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_BYTES_READ, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::EXECUTED_REPLIES, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_PARITY_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::COMMAND_REPLIES, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_NOISE_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_BYTES_WRITTEN, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_FRAME_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_BYTES_READ, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_REG_OVERRUN_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_PARITY_ERRORS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::UART_TOTAL_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_NOISE_ERRORS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::SPI_BYTES_WRITTEN, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_FRAME_ERRORS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::SPI_BYTES_READ, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_REG_OVERRUN_ERRORS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::SPI_REG_OVERRUN_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::UART_TOTAL_ERRORS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(RwDefinitions::SPI_TOTAL_ERRORS, new PoolEntry<uint32_t>({0})); localDataPoolMap.emplace(rws::SPI_BYTES_WRITTEN, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(rws::SPI_BYTES_READ, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(rws::SPI_REG_OVERRUN_ERRORS, new PoolEntry<uint32_t>({0}));
localDataPoolMap.emplace(rws::SPI_TOTAL_ERRORS, new PoolEntry<uint32_t>({0}));
poolManager.subscribeForDiagPeriodicPacket( poolManager.subscribeForDiagPeriodicPacket(
subdp::DiagnosticsHkPeriodicParams(statusSet.getSid(), false, 5.0)); subdp::DiagnosticsHkPeriodicParams(statusSet.getSid(), false, 5.0));
poolManager.subscribeForRegularPeriodicPacket( poolManager.subscribeForRegularPeriodicPacket(
@ -286,26 +302,15 @@ ReturnValue_t RwHandler::initializeLocalDataPool(localpool::DataPool& localDataP
return returnvalue::OK; return returnvalue::OK;
} }
void RwHandler::prepareSimpleCommand(DeviceCommandId_t id) { ReturnValue_t RwHandler::checkSpeedAndRampTime() {
commandBuffer[0] = static_cast<uint8_t>(id); int32_t speed = 0;
uint16_t crc = CRC::crc16ccitt(commandBuffer, 1, 0xFFFF); uint16_t rampTime = 0;
commandBuffer[1] = static_cast<uint8_t>(crc & 0xFF); rwSpeedActuationSet.getRwSpeed(speed, rampTime);
commandBuffer[2] = static_cast<uint8_t>(crc >> 8 & 0xFF);
rawPacket = commandBuffer;
rawPacketLen = 3;
}
ReturnValue_t RwHandler::checkSpeedAndRampTime(const uint8_t* commandData, size_t commandDataLen) {
int32_t speed =
*commandData << 24 | *(commandData + 1) << 16 | *(commandData + 2) << 8 | *(commandData + 3);
if ((speed < -65000 || speed > 65000 || (speed > -1000 && speed < 1000)) && (speed != 0)) { if ((speed < -65000 || speed > 65000 || (speed > -1000 && speed < 1000)) && (speed != 0)) {
sif::error << "RwHandler::checkSpeedAndRampTime: Command has invalid speed" << std::endl; sif::error << "RwHandler::checkSpeedAndRampTime: Command has invalid speed" << std::endl;
return INVALID_SPEED; return INVALID_SPEED;
} }
uint16_t rampTime = (*(commandData + 4) << 8) | *(commandData + 5);
if (rampTime < 10 || rampTime > 20000) { if (rampTime < 10 || rampTime > 20000) {
sif::error << "RwHandler::checkSpeedAndRampTime: Command has invalid ramp time" << std::endl; sif::error << "RwHandler::checkSpeedAndRampTime: Command has invalid ramp time" << std::endl;
return INVALID_RAMP_TIME; return INVALID_RAMP_TIME;
@ -314,33 +319,14 @@ ReturnValue_t RwHandler::checkSpeedAndRampTime(const uint8_t* commandData, size_
return returnvalue::OK; return returnvalue::OK;
} }
void RwHandler::prepareSetSpeedCmd(const uint8_t* commandData, size_t commandDataLen) {
commandBuffer[0] = static_cast<uint8_t>(RwDefinitions::SET_SPEED);
/** Speed (0.1 RPM) */
commandBuffer[1] = *(commandData + 3);
commandBuffer[2] = *(commandData + 2);
commandBuffer[3] = *(commandData + 1);
commandBuffer[4] = *commandData;
/** Ramp time (ms) */
commandBuffer[5] = *(commandData + 5);
commandBuffer[6] = *(commandData + 4);
uint16_t crc = CRC::crc16ccitt(commandBuffer, 7, 0xFFFF);
commandBuffer[7] = static_cast<uint8_t>(crc & 0xFF);
commandBuffer[8] = static_cast<uint8_t>(crc >> 8 & 0xFF);
rawPacket = commandBuffer;
rawPacketLen = 9;
}
void RwHandler::handleResetStatusReply(const uint8_t* packet) { void RwHandler::handleResetStatusReply(const uint8_t* packet) {
PoolReadGuard rg(&lastResetStatusSet); PoolReadGuard rg(&lastResetStatusSet);
uint8_t offset = 2; uint8_t offset = 2;
uint8_t resetStatus = packet[offset]; uint8_t resetStatus = packet[offset];
if (resetStatus != 0) { if (resetStatus != 0) {
internalState = InternalState::CLEAR_RESET_STATUS; // internalState = InternalState::CLEAR_RESET_STATUS;
lastResetStatusSet.lastNonClearedResetStatus = resetStatus; lastResetStatusSet.lastNonClearedResetStatus = resetStatus;
triggerEvent(RwDefinitions::RESET_OCCURED, resetStatus, 0); triggerEvent(rws::RESET_OCCURED, resetStatus, 0);
} }
lastResetStatusSet.currentResetStatus = resetStatus; lastResetStatusSet.currentResetStatus = resetStatus;
if (debugMode) { if (debugMode) {
@ -379,10 +365,10 @@ void RwHandler::handleGetRwStatusReply(const uint8_t* packet) {
statusSet.setValidity(true, true); statusSet.setValidity(true, true);
if (statusSet.state == RwDefinitions::STATE_ERROR) { if (statusSet.state == rws::STATE_ERROR) {
// This requires the commanding of the init reaction wheel controller command to recover // This requires the commanding of the init reaction wheel controller command to recover
// from error state which must be handled by the FDIR instance. // from error state which must be handled by the FDIR instance.
triggerEvent(RwDefinitions::ERROR_STATE, statusSet.state.value, 0); triggerEvent(rws::ERROR_STATE, statusSet.state.value, 0);
sif::error << "RwHandler::handleGetRwStatusReply: Reaction wheel in error state" << std::endl; sif::error << "RwHandler::handleGetRwStatusReply: Reaction wheel in error state" << std::endl;
} }
@ -413,6 +399,24 @@ void RwHandler::handleTemperatureReply(const uint8_t* packet) {
} }
} }
LocalPoolDataSetBase* RwHandler::getDataSetHandle(sid_t sid) {
switch (sid.ownerSetId) {
case (rws::SetIds::STATUS_SET_ID): {
return &statusSet;
}
case (rws::SetIds::LAST_RESET_ID): {
return &lastResetStatusSet;
}
case (rws::SetIds::SPEED_CMD_SET): {
return &rwSpeedActuationSet;
}
case (rws::SetIds::TM_SET_ID): {
return &tmDataset;
}
}
return nullptr;
}
void RwHandler::handleGetTelemetryReply(const uint8_t* packet) { void RwHandler::handleGetTelemetryReply(const uint8_t* packet) {
PoolReadGuard rg(&tmDataset); PoolReadGuard rg(&tmDataset);
uint8_t offset = 2; uint8_t offset = 2;

View File

@ -3,12 +3,14 @@
#include <fsfw/devicehandlers/DeviceHandlerBase.h> #include <fsfw/devicehandlers/DeviceHandlerBase.h>
#include <fsfw_hal/common/gpio/gpioDefinitions.h> #include <fsfw_hal/common/gpio/gpioDefinitions.h>
#include <mission/devices/devicedefinitions/RwDefinitions.h> #include <mission/devices/devicedefinitions/rwHelpers.h>
#include <string.h> #include <string.h>
#include "events/subsystemIdRanges.h" #include "events/subsystemIdRanges.h"
#include "returnvalues/classIds.h" #include "returnvalues/classIds.h"
static constexpr bool ACTUATION_WIRETAPPING = false;
class GpioIF; class GpioIF;
/** /**
@ -34,30 +36,12 @@ class RwHandler : public DeviceHandlerBase {
* to high to enable the device. * to high to enable the device.
*/ */
RwHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie, GpioIF* gpioComIF, RwHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie, GpioIF* gpioComIF,
gpioId_t enableGpio); gpioId_t enableGpio, uint8_t rwIdx);
void setDebugMode(bool enable); void setDebugMode(bool enable);
virtual ~RwHandler(); virtual ~RwHandler();
static const uint8_t INTERFACE_ID = CLASS_ID::RW_HANDLER;
static const ReturnValue_t SPI_WRITE_FAILURE = MAKE_RETURN_CODE(0xB0);
//! [EXPORT] : [COMMENT] Used by the spi send function to tell a failing read call
static const ReturnValue_t SPI_READ_FAILURE = MAKE_RETURN_CODE(0xB1);
//! [EXPORT] : [COMMENT] Can be used by the HDLC decoding mechanism to inform about a missing
//! start sign 0x7E
static const ReturnValue_t MISSING_START_SIGN = MAKE_RETURN_CODE(0xB2);
//! [EXPORT] : [COMMENT] Can be used by the HDLC decoding mechanism to inform about an invalid
//! substitution combination
static const ReturnValue_t INVALID_SUBSTITUTE = MAKE_RETURN_CODE(0xB3);
//! [EXPORT] : [COMMENT] HDLC decoding mechanism never receives the end sign 0x7E
static const ReturnValue_t MISSING_END_SIGN = MAKE_RETURN_CODE(0xB4);
//! [EXPORT] : [COMMENT] Reaction wheel only responds with empty frames.
static const ReturnValue_t NO_REPLY = MAKE_RETURN_CODE(0xB5);
//! [EXPORT] : [COMMENT] Expected a start marker as first byte
static const ReturnValue_t NO_START_MARKER = MAKE_RETURN_CODE(0xB6);
protected: protected:
void doStartUp() override; void doStartUp() override;
void doShutDown() override; void doShutDown() override;
@ -72,6 +56,7 @@ class RwHandler : public DeviceHandlerBase {
uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override; uint32_t getTransitionDelayMs(Mode_t modeFrom, Mode_t modeTo) override;
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap, ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
LocalDataPoolManager& poolManager) override; LocalDataPoolManager& poolManager) override;
LocalPoolDataSetBase* getDataSetHandle(sid_t sid) override;
private: private:
//! [EXPORT] : [COMMENT] Action Message with invalid speed was received. Valid speeds must be in //! [EXPORT] : [COMMENT] Action Message with invalid speed was received. Valid speeds must be in
@ -85,42 +70,57 @@ class RwHandler : public DeviceHandlerBase {
static const ReturnValue_t EXECUTION_FAILED = MAKE_RETURN_CODE(0xA3); static const ReturnValue_t EXECUTION_FAILED = MAKE_RETURN_CODE(0xA3);
//! [EXPORT] : [COMMENT] Reaction wheel reply has invalid crc //! [EXPORT] : [COMMENT] Reaction wheel reply has invalid crc
static const ReturnValue_t CRC_ERROR = MAKE_RETURN_CODE(0xA4); static const ReturnValue_t CRC_ERROR = MAKE_RETURN_CODE(0xA4);
static const ReturnValue_t VALUE_NOT_READ = MAKE_RETURN_CODE(0xA5);
GpioIF* gpioComIF = nullptr; GpioIF* gpioComIF = nullptr;
gpioId_t enableGpio = gpio::NO_GPIO; gpioId_t enableGpio = gpio::NO_GPIO;
bool debugMode = false; bool debugMode = false;
RwDefinitions::StatusSet statusSet; rws::StatusSet statusSet;
RwDefinitions::LastResetSatus lastResetStatusSet; rws::LastResetSatus lastResetStatusSet;
RwDefinitions::TmDataset tmDataset; rws::TmDataset tmDataset;
rws::RwSpeedActuationSet rwSpeedActuationSet;
uint8_t commandBuffer[RwDefinitions::MAX_CMD_SIZE]; uint8_t commandBuffer[32];
uint8_t rwIdx;
enum class InternalState { GET_RESET_STATUS, CLEAR_RESET_STATUS, READ_TEMPERATURE, GET_RW_SATUS }; PoolEntry<int32_t> rwSpeed = PoolEntry<int32_t>({0});
PoolEntry<uint16_t> rampTime = PoolEntry<uint16_t>({10});
InternalState internalState = InternalState::GET_RESET_STATUS; enum class InternalState {
DEFAULT,
GET_TM,
INIT_RW_CONTROLLER,
RESET_MCU,
// GET_RESET_STATUS,
// CLEAR_RESET_STATUS,
// READ_TEMPERATURE,
// SET_SPEED,
// GET_RW_SATUS
};
size_t sizeOfReply = 0; InternalState internalState = InternalState::DEFAULT;
/** /**
* @brief This function can be used to build commands which do not contain any data apart * @brief This function can be used to build commands which do not contain any data apart
* from the command id and the CRC. * from the command id and the CRC.
* @param commandId The command id of the command to build. * @param commandId The command id of the command to build.
*/ */
void prepareSimpleCommand(DeviceCommandId_t id); // void prepareSimpleCommand(DeviceCommandId_t id);
/** /**
* @brief This function checks if the receiced speed and ramp time to set are in a valid * @brief This function checks if the receiced speed and ramp time to set are in a valid
* range. * range.
* @return returnvalue::OK if successful, otherwise error code. * @return returnvalue::OK if successful, otherwise error code.
*/ */
ReturnValue_t checkSpeedAndRampTime(const uint8_t* commandData, size_t commandDataLen); ReturnValue_t checkSpeedAndRampTime();
/** /**
* @brief This function prepares the set speed command from the commandData received with * @brief This function prepares the set speed command from the dataSet received with
* an action message. * an action message or set in the software.
* @return returnvalue::OK if successful, otherwise error code.
*/ */
void prepareSetSpeedCmd(const uint8_t* commandData, size_t commandDataLen); // ReturnValue_t prepareSetSpeedCmd();
/** /**
* @brief This function writes the last reset status retrieved with the get last reset status * @brief This function writes the last reset status retrieved with the get last reset status

View File

@ -1 +1 @@
target_sources(${LIB_EIVE_MISSION} PRIVATE ScexDefinitions.cpp) target_sources(${LIB_EIVE_MISSION} PRIVATE ScexDefinitions.cpp rwHelpers.cpp)

View File

@ -492,14 +492,14 @@ class DipoleActuationSet : public StaticLocalDataSet<4> {
void setDipoles(int16_t xDipole_, int16_t yDipole_, int16_t zDipole_, void setDipoles(int16_t xDipole_, int16_t yDipole_, int16_t zDipole_,
uint16_t currentTorqueDurationMs_) { uint16_t currentTorqueDurationMs_) {
if (xDipole.value != xDipole_) { if (xDipole.value != xDipole_) {
xDipole = xDipole_;
} }
xDipole = xDipole_;
if (yDipole.value != yDipole_) { if (yDipole.value != yDipole_) {
yDipole = yDipole_;
} }
yDipole = yDipole_;
if (zDipole.value != zDipole_) { if (zDipole.value != zDipole_) {
zDipole = zDipole_;
} }
zDipole = zDipole_;
currentTorqueDurationMs = currentTorqueDurationMs_; currentTorqueDurationMs = currentTorqueDurationMs_;
} }

View File

@ -0,0 +1,54 @@
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_RWHELPERS_CPP_
#define MISSION_DEVICES_DEVICEDEFINITIONS_RWHELPERS_CPP_
#include "rwHelpers.h"
void rws::encodeHdlc(const uint8_t* sourceBuf, size_t sourceLen, uint8_t* encodedBuffer,
size_t& encodedLen) {
encodedBuffer[0] = rws::FRAME_DELIMITER;
encodedLen = 1;
for (size_t sourceIdx = 0; sourceIdx < sourceLen; sourceIdx++) {
if (sourceBuf[sourceIdx] == 0x7E) {
encodedBuffer[encodedLen++] = 0x7D;
encodedBuffer[encodedLen++] = 0x5E;
} else if (sourceBuf[sourceIdx] == 0x7D) {
encodedBuffer[encodedLen++] = 0x7D;
encodedBuffer[encodedLen++] = 0x5D;
} else {
encodedBuffer[encodedLen++] = sourceBuf[sourceIdx];
}
}
encodedBuffer[encodedLen++] = rws::FRAME_DELIMITER;
}
size_t rws::idToPacketLen(DeviceCommandId_t id) {
switch (id) {
case (rws::GET_RW_STATUS): {
return rws::SIZE_GET_RW_STATUS;
}
case (rws::SET_SPEED): {
return rws::SIZE_SET_SPEED_REPLY;
}
case (rws::CLEAR_LAST_RESET_STATUS): {
return rws::SIZE_CLEAR_RESET_STATUS;
}
case (rws::GET_LAST_RESET_STATUS): {
return rws::SIZE_GET_RESET_STATUS;
}
case (rws::GET_TEMPERATURE): {
return rws::SIZE_GET_TEMPERATURE_REPLY;
}
case (rws::GET_TM): {
return rws::SIZE_GET_TELEMETRY_REPLY;
}
case (rws::INIT_RW_CONTROLLER): {
return rws::SIZE_INIT_RW;
}
default: {
sif::error << "no reply buffer for rw command " << id << std::endl;
return 0;
}
}
}
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_RWHELPERS_CPP_ */

View File

@ -1,14 +1,60 @@
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_RWDEFINITIONS_H_ #ifndef MISSION_DEVICES_DEVICEDEFINITIONS_RWHELPERS_H_
#define MISSION_DEVICES_DEVICEDEFINITIONS_RWDEFINITIONS_H_ #define MISSION_DEVICES_DEVICEDEFINITIONS_RWHELPERS_H_
#include <fsfw/datapoollocal/LocalPoolVariable.h> #include <fsfw/datapoollocal/LocalPoolVariable.h>
#include <fsfw/datapoollocal/StaticLocalDataSet.h> #include <fsfw/datapoollocal/StaticLocalDataSet.h>
#include <fsfw/devicehandlers/DeviceHandlerIF.h> #include <fsfw/devicehandlers/DeviceHandlerIF.h>
#include "eive/resultClassIds.h"
#include "events/subsystemIdRanges.h" #include "events/subsystemIdRanges.h"
#include "objects/systemObjectList.h" #include "objects/systemObjectList.h"
namespace RwDefinitions { namespace rws {
void encodeHdlc(const uint8_t* sourceBuf, size_t sourceLen, uint8_t* encodedBuffer,
size_t& encodedLen);
size_t idToPacketLen(DeviceCommandId_t id);
static const size_t SIZE_GET_RESET_STATUS = 5;
static const size_t SIZE_CLEAR_RESET_STATUS = 4;
static const size_t SIZE_INIT_RW = 4;
static const size_t SIZE_GET_RW_STATUS = 14;
static const size_t SIZE_SET_SPEED_REPLY = 4;
static const size_t SIZE_GET_TEMPERATURE_REPLY = 8;
/** Max size when requesting telemetry */
static const size_t SIZE_GET_TELEMETRY_REPLY = 91;
//! This is the end and start marker of the frame datalinklayer. Also called frame delimiter
//! in the NanoAvionics datasheet.
static constexpr uint8_t FRAME_DELIMITER = 0x7E;
enum class SpecialRwRequest : uint8_t {
REQUEST_NONE = 0,
RESET_MCU = 1,
INIT_RW_CONTROLLER = 2,
GET_TM = 3,
NUM_REQUESTS
};
static const uint8_t INTERFACE_ID = CLASS_ID::RW_HANDLER;
static const ReturnValue_t SPI_WRITE_FAILURE = MAKE_RETURN_CODE(0xB0);
//! [EXPORT] : [COMMENT] Used by the spi send function to tell a failing read call
static const ReturnValue_t SPI_READ_FAILURE = MAKE_RETURN_CODE(0xB1);
//! [EXPORT] : [COMMENT] Can be used by the HDLC decoding mechanism to inform about a missing
//! start sign 0x7E
static const ReturnValue_t MISSING_START_SIGN = MAKE_RETURN_CODE(0xB2);
//! [EXPORT] : [COMMENT] Can be used by the HDLC decoding mechanism to inform about an invalid
//! substitution combination
static const ReturnValue_t INVALID_SUBSTITUTE = MAKE_RETURN_CODE(0xB3);
//! [EXPORT] : [COMMENT] HDLC decoding mechanism never receives the end sign 0x7E
static const ReturnValue_t MISSING_END_SIGN = MAKE_RETURN_CODE(0xB4);
//! [EXPORT] : [COMMENT] Reaction wheel only responds with empty frames.
static const ReturnValue_t NO_REPLY = MAKE_RETURN_CODE(0xB5);
//! [EXPORT] : [COMMENT] Expected a start marker as first byte
static const ReturnValue_t NO_START_MARKER = MAKE_RETURN_CODE(0xB6);
//! [EXPORT] : [COMMENT] Timeout when reading reply
static const ReturnValue_t SPI_READ_TIMEOUT = MAKE_RETURN_CODE(0xB7);
static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::RW_HANDLER; static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::RW_HANDLER;
@ -17,7 +63,8 @@ static constexpr Event ERROR_STATE = MAKE_EVENT(1, severity::HIGH);
static constexpr Event RESET_OCCURED = event::makeEvent(SUBSYSTEM_ID, 2, severity::LOW); static constexpr Event RESET_OCCURED = event::makeEvent(SUBSYSTEM_ID, 2, severity::LOW);
static const uint32_t SPI_REPLY_DELAY = 70000; // us //! Minimal delay as specified by the datasheet.
static const uint32_t SPI_REPLY_DELAY = 20000; // us
enum PoolIds : lp_id_t { enum PoolIds : lp_id_t {
TEMPERATURE_C, TEMPERATURE_C,
@ -51,7 +98,10 @@ enum PoolIds : lp_id_t {
SPI_BYTES_WRITTEN, SPI_BYTES_WRITTEN,
SPI_BYTES_READ, SPI_BYTES_READ,
SPI_REG_OVERRUN_ERRORS, SPI_REG_OVERRUN_ERRORS,
SPI_TOTAL_ERRORS SPI_TOTAL_ERRORS,
RW_SPEED,
RAMP_TIME,
}; };
enum States : uint8_t { STATE_ERROR, IDLE, COASTING, RUNNING_SPEED_STABLE, RUNNING_SPEED_CHANGING }; enum States : uint8_t { STATE_ERROR, IDLE, COASTING, RUNNING_SPEED_STABLE, RUNNING_SPEED_CHANGING };
@ -65,29 +115,28 @@ enum LastResetStatusBitPos : uint8_t {
LOW_POWER_RESET = 5 LOW_POWER_RESET = 5
}; };
static const DeviceCommandId_t RESET_MCU = 1; enum DeviceCommandId : DeviceCommandId_t {
static const DeviceCommandId_t GET_LAST_RESET_STATUS = 2; RESET_MCU = 1,
static const DeviceCommandId_t CLEAR_LAST_RESET_STATUS = 3;
static const DeviceCommandId_t GET_RW_STATUS = 4;
/** This command is needed to recover from error state */
static const DeviceCommandId_t INIT_RW_CONTROLLER = 5;
static const DeviceCommandId_t SET_SPEED = 6;
static const DeviceCommandId_t GET_TEMPERATURE = 8;
static const DeviceCommandId_t GET_TM = 9;
static const uint32_t TEMPERATURE_SET_ID = GET_TEMPERATURE; GET_LAST_RESET_STATUS = 2,
static const uint32_t STATUS_SET_ID = GET_RW_STATUS; CLEAR_LAST_RESET_STATUS = 3,
static const uint32_t LAST_RESET_ID = GET_LAST_RESET_STATUS; GET_RW_STATUS = 4,
static const uint32_t TM_SET_ID = GET_TM; INIT_RW_CONTROLLER = 5,
SET_SPEED = 6,
GET_TEMPERATURE = 8,
GET_TM = 9
};
static const size_t SIZE_GET_RESET_STATUS = 5; static constexpr DeviceCommandId_t REQUEST_ID = 0x77;
static const size_t SIZE_CLEAR_RESET_STATUS = 4; static constexpr DeviceCommandId_t REPLY_ID = 0x78;
static const size_t SIZE_INIT_RW = 4;
static const size_t SIZE_GET_RW_STATUS = 14; enum SetIds : uint32_t {
static const size_t SIZE_SET_SPEED_REPLY = 4; TEMPERATURE_SET_ID = DeviceCommandId::GET_TEMPERATURE,
static const size_t SIZE_GET_TEMPERATURE_REPLY = 8; STATUS_SET_ID = DeviceCommandId::GET_RW_STATUS,
/** Max size when requesting telemetry */ LAST_RESET_ID = DeviceCommandId::GET_LAST_RESET_STATUS,
static const size_t SIZE_GET_TELEMETRY_REPLY = 91; TM_SET_ID = DeviceCommandId::GET_TM,
SPEED_CMD_SET = 10,
};
/** Set speed command has maximum size */ /** Set speed command has maximum size */
static const size_t MAX_CMD_SIZE = 9; static const size_t MAX_CMD_SIZE = 9;
@ -106,9 +155,10 @@ static const uint8_t TM_SET_ENTRIES = 24;
*/ */
class StatusSet : public StaticLocalDataSet<STATUS_SET_ENTRIES> { class StatusSet : public StaticLocalDataSet<STATUS_SET_ENTRIES> {
public: public:
StatusSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, STATUS_SET_ID) {} StatusSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, rws::SetIds::STATUS_SET_ID) {}
StatusSet(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, STATUS_SET_ID)) {} StatusSet(object_id_t objectId)
: StaticLocalDataSet(sid_t(objectId, rws::SetIds::STATUS_SET_ID)) {}
lp_var_t<int32_t> temperatureCelcius = lp_var_t<int32_t> temperatureCelcius =
lp_var_t<int32_t>(sid.objectId, PoolIds::TEMPERATURE_C, this); lp_var_t<int32_t>(sid.objectId, PoolIds::TEMPERATURE_C, this);
@ -124,9 +174,11 @@ class StatusSet : public StaticLocalDataSet<STATUS_SET_ENTRIES> {
*/ */
class LastResetSatus : public StaticLocalDataSet<LAST_RESET_ENTRIES> { class LastResetSatus : public StaticLocalDataSet<LAST_RESET_ENTRIES> {
public: public:
LastResetSatus(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, LAST_RESET_ID) {} LastResetSatus(HasLocalDataPoolIF* owner)
: StaticLocalDataSet(owner, rws::SetIds::LAST_RESET_ID) {}
LastResetSatus(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, LAST_RESET_ID)) {} LastResetSatus(object_id_t objectId)
: StaticLocalDataSet(sid_t(objectId, rws::SetIds::LAST_RESET_ID)) {}
// If a reset occurs, the status code will be cached into this variable // If a reset occurs, the status code will be cached into this variable
lp_var_t<uint8_t> lastNonClearedResetStatus = lp_var_t<uint8_t> lastNonClearedResetStatus =
@ -143,9 +195,9 @@ class LastResetSatus : public StaticLocalDataSet<LAST_RESET_ENTRIES> {
*/ */
class TmDataset : public StaticLocalDataSet<TM_SET_ENTRIES> { class TmDataset : public StaticLocalDataSet<TM_SET_ENTRIES> {
public: public:
TmDataset(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, TM_SET_ID) {} TmDataset(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, rws::SetIds::TM_SET_ID) {}
TmDataset(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, TM_SET_ID)) {} TmDataset(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, rws::SetIds::TM_SET_ID)) {}
lp_var_t<uint8_t> lastResetStatus = lp_var_t<uint8_t> lastResetStatus =
lp_var_t<uint8_t>(sid.objectId, PoolIds::TM_LAST_RESET_STATUS, this); lp_var_t<uint8_t>(sid.objectId, PoolIds::TM_LAST_RESET_STATUS, this);
@ -192,6 +244,95 @@ class TmDataset : public StaticLocalDataSet<TM_SET_ENTRIES> {
lp_var_t<uint32_t>(sid.objectId, PoolIds::SPI_TOTAL_ERRORS, this); lp_var_t<uint32_t>(sid.objectId, PoolIds::SPI_TOTAL_ERRORS, this);
}; };
} // namespace RwDefinitions class RwSpeedActuationSet : public StaticLocalDataSet<2> {
friend class RwHandler;
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_RWDEFINITIONS_H_ */ public:
RwSpeedActuationSet(HasLocalDataPoolIF& owner)
: StaticLocalDataSet(&owner, rws::SetIds::SPEED_CMD_SET) {}
RwSpeedActuationSet(object_id_t objectId)
: StaticLocalDataSet(sid_t(objectId, rws::SetIds::SPEED_CMD_SET)) {}
void setRwSpeed(int32_t rwSpeed_, uint16_t rampTime_) {
if (rwSpeed.value != rwSpeed_) {
rwSpeed = rwSpeed_;
}
if (rampTime.value != rampTime_) {
rampTime = rampTime_;
}
}
void getRwSpeed(int32_t& rwSpeed_, uint16_t& rampTime_) {
rwSpeed_ = rwSpeed.value;
rampTime_ = rampTime.value;
}
private:
lp_var_t<int32_t> rwSpeed = lp_var_t<int32_t>(sid.objectId, rws::PoolIds::RW_SPEED, this);
lp_var_t<uint16_t> rampTime = lp_var_t<uint16_t>(sid.objectId, rws::PoolIds::RAMP_TIME, this);
};
} // namespace rws
/**
* Raw pointer overlay to hold the different frames received from the reaction
* wheel in a raw buffer and send them to the device handler.
*/
struct RwReplies {
friend class RwPollingTask;
public:
RwReplies(const uint8_t* rawData) : rawData(const_cast<uint8_t*>(rawData)) { initPointers(); }
const uint8_t* getClearLastResetStatusReply() const { return clearLastResetStatusReply + 1; }
bool wasClearLastRsetStatusReplyRead() const { return clearLastResetStatusReply[0]; }
const uint8_t* getGetLastResetStatusReply() const { return getLastResetStatusReply + 1; }
bool wasGetLastStatusReplyRead() const { return getLastResetStatusReply[0]; }
const uint8_t* getHkDataReply() const { return hkDataReply + 1; }
bool wasHkDataReplyRead() const { return hkDataReply[0]; }
const uint8_t* getInitRwControllerReply() const { return initRwControllerReply + 1; }
bool wasInitRwControllerReplyRead() const { return initRwControllerReply[0]; }
const uint8_t* getRawData() const { return rawData; }
const uint8_t* getReadTemperatureReply() const { return readTemperatureReply + 1; }
bool wasReadTemperatureReplySet() const { return readTemperatureReply[0]; }
const uint8_t* getRwStatusReply() const { return rwStatusReply + 1; }
bool wasRwStatusRead() const { return rwStatusReply[0]; }
const uint8_t* getSetSpeedReply() const { return setSpeedReply + 1; }
bool wasSetSpeedReplyRead() const { return setSpeedReply[0]; }
private:
RwReplies(uint8_t* rwData) : rawData(rwData) { initPointers(); }
/**
* The first byte of the reply buffers contains a flag which shows whether that
* frame was read from the reaction wheel at least once.
*/
void initPointers() {
rwStatusReply = rawData;
setSpeedReply = rawData + rws::SIZE_GET_RW_STATUS + 1;
getLastResetStatusReply = setSpeedReply + rws::SIZE_SET_SPEED_REPLY + 1;
clearLastResetStatusReply = getLastResetStatusReply + rws::SIZE_GET_RESET_STATUS + 1;
readTemperatureReply = clearLastResetStatusReply + rws::SIZE_CLEAR_RESET_STATUS + 1;
hkDataReply = readTemperatureReply + rws::SIZE_GET_TEMPERATURE_REPLY + 1;
initRwControllerReply = hkDataReply + rws::SIZE_GET_TELEMETRY_REPLY + 1;
dummyPointer = initRwControllerReply + rws::SIZE_INIT_RW + 1;
}
uint8_t* rawData;
uint8_t* rwStatusReply;
uint8_t* setSpeedReply;
uint8_t* getLastResetStatusReply;
uint8_t* clearLastResetStatusReply;
uint8_t* readTemperatureReply;
uint8_t* hkDataReply;
uint8_t* initRwControllerReply;
uint8_t* dummyPointer;
};
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_RWHELPERS_H_ */

View File

@ -42,6 +42,11 @@ ReturnValue_t AcsSubsystem::initialize() {
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
sif::error << "AcsSubsystem: Subscribing for acs::SAFE_RATE_RECOVERY failed" << std::endl; sif::error << "AcsSubsystem: Subscribing for acs::SAFE_RATE_RECOVERY failed" << std::endl;
} }
result =
manager->subscribeToEvent(eventQueue->getId(), event::getEventId(acs::MULTIPLE_RW_INVALID));
if (result != returnvalue::OK) {
sif::error << "AcsSubsystem: Subscribing for acs::MULTIPLE_RW_INVALID failed" << std::endl;
}
return Subsystem::initialize(); return Subsystem::initialize();
} }
@ -64,12 +69,13 @@ void AcsSubsystem::handleEventMessages() {
sif::error << "AcsSubsystem: sending DETUMBLE mode cmd to self has failed" << std::endl; sif::error << "AcsSubsystem: sending DETUMBLE mode cmd to self has failed" << std::endl;
} }
} }
if (event.getEvent() == acs::SAFE_RATE_RECOVERY) { if (event.getEvent() == acs::SAFE_RATE_RECOVERY ||
event.getEvent() == acs::MULTIPLE_RW_INVALID) {
CommandMessage msg; CommandMessage msg;
ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, 0); ModeMessage::setCmdModeMessage(msg, acs::AcsMode::SAFE, 0);
ReturnValue_t result = commandQueue->sendMessage(commandQueue->getId(), &msg); ReturnValue_t result = commandQueue->sendMessage(commandQueue->getId(), &msg);
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
sif::error << "AcsSubsystem: sending IDLE mode cmd to self has failed" << std::endl; sif::error << "AcsSubsystem: sending SAFE mode cmd to self has failed" << std::endl;
} }
} }
break; break;

View File

@ -167,7 +167,12 @@ bool RwAssembly::isUseable(object_id_t object, Mode_t mode) {
return false; return false;
} }
ReturnValue_t RwAssembly::initialize() { return SubsystemBase::initialize(); } ReturnValue_t RwAssembly::initialize() {
for (auto objId : helper.rwIds) {
updateChildModeByObjId(objId, MODE_OFF, SUBMODE_NONE);
}
return AssemblyBase::initialize();
}
void RwAssembly::handleModeTransitionFailed(ReturnValue_t result) { void RwAssembly::handleModeTransitionFailed(ReturnValue_t result) {
if (targetMode == MODE_OFF) { if (targetMode == MODE_OFF) {

2
tmtc

@ -1 +1 @@
Subproject commit 1e143ea6faa608baf3118512416f5a495dbd606c Subproject commit d9945d4054ad07dd6b17df798ca76220abfe1c6d

View File

@ -5,5 +5,6 @@ target_sources(${UNITTEST_NAME} PRIVATE
main.cpp main.cpp
testEnvironment.cpp testEnvironment.cpp
testStampInFilename.cpp testStampInFilename.cpp
hdlcEncodingRw.cpp
printChar.cpp printChar.cpp
) )

View File

@ -0,0 +1,38 @@
#include <catch2/catch_test_macros.hpp>
#include "mission/devices/devicedefinitions/rwHelpers.h"
TEST_CASE("HDLC Encoding RW", "[acs]") {
std::array<uint8_t, 256> encodedBuffer{};
size_t encodedLen = 0;
SECTION("Basic No Escaped Bytes") {
std::array<uint8_t, 4> dummyNoEscaped = {1, 2, 3, 4};
rws::encodeHdlc(dummyNoEscaped.data(), dummyNoEscaped.size(), encodedBuffer.data(), encodedLen);
REQUIRE(encodedLen == 6);
REQUIRE(encodedBuffer[0] == rws::FRAME_DELIMITER);
REQUIRE(encodedBuffer[1] == 1);
REQUIRE(encodedBuffer[2] == 2);
REQUIRE(encodedBuffer[3] == 3);
REQUIRE(encodedBuffer[4] == 4);
REQUIRE(encodedBuffer[5] == rws::FRAME_DELIMITER);
}
SECTION("Basic Some Escaped Bytes") {
std::array<uint8_t, 4> dummySomeEscaped = {1, 0x7D, 0x7E, 4};
rws::encodeHdlc(dummySomeEscaped.data(), dummySomeEscaped.size(), encodedBuffer.data(),
encodedLen);
REQUIRE(encodedLen == 8);
REQUIRE(encodedBuffer[0] == rws::FRAME_DELIMITER);
REQUIRE(encodedBuffer[1] == 1);
REQUIRE(encodedBuffer[2] == 0x7D);
REQUIRE(encodedBuffer[3] == 0x5D);
REQUIRE(encodedBuffer[4] == 0x7D);
REQUIRE(encodedBuffer[5] == 0x5E);
REQUIRE(encodedBuffer[6] == 4);
REQUIRE(encodedBuffer[7] == rws::FRAME_DELIMITER);
}
}