merged develop

This commit is contained in:
Jakob Meier 2023-02-20 14:34:57 +01:00
commit 6074e9246e
66 changed files with 1460 additions and 771 deletions

16
.idea/cmake.xml Normal file
View File

@ -0,0 +1,16 @@
<?xml version="1.0" encoding="UTF-8"?>
<project version="4">
<component name="CMakeSharedSettings">
<configurations>
<configuration PROFILE_NAME="Debug" ENABLED="true" CONFIG_NAME="Debug" NO_GENERATOR="true" />
<configuration PROFILE_NAME="Debug Q7S" ENABLED="true" CONFIG_NAME="Debug" TOOLCHAIN_NAME="Q7S" GENERATION_OPTIONS="-DTGT_BSP=&quot;arm/q7s&quot;" NO_GENERATOR="true">
<ADDITIONAL_GENERATION_ENVIRONMENT>
<envs>
<env name="ZYNQ_7020_ROOTFS" value="/opt/xiphos/sdk/ark/sysroots/cortexa9hf-neon-xiphos-linux-gnueabi" />
<env name="CROSS_COMPILE" value="/opt/q7s-gcc/gcc-arm-8.3-2019.03-x86_64-arm-linux-gnueabihf/bin/arm-linux-gnueabihf" />
</envs>
</ADDITIONAL_GENERATION_ENVIRONMENT>
</configuration>
</configurations>
</component>
</project>

View File

@ -19,19 +19,46 @@ change warranting a new major release:
## Changed ## Changed
- Add `-Wshadow=local` shadowing warnings and fixed all of them
## Added
- git post checkout hook which initializes and updates the submodules
automatically.
# [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
- Igrf13 model vector now outputs as uT instead of nT - Igrf13 model vector now outputs as uT instead of nT
- Changed timings for `AcsPst` - Changed timings for `AcsPst`, more time for sun sensors.
- Added values for MGM sensor fusion - 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
- Fixed values for GYR sensor fusion - 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 # [v1.27.2] 2023-02-14
Reaction Wheel handling was determined to be (quasi) broken and needs to be fixed in future release Reaction Wheel handling was determined to be (quasi) broken and needs to be fixed in future release
to be usable by ACS controller. to be usable by ACS controller.
eive-tmtc: v2.15.6 eive-tmtc: v2.12.6
## Added ## Added

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 2) set(OBSW_VERSION_REVISION 0)
# set(CMAKE_VERBOSE TRUE) # set(CMAKE_VERBOSE TRUE)
@ -358,6 +358,7 @@ if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU")
"-Wimplicit-fallthrough=1" "-Wimplicit-fallthrough=1"
"-Wno-unused-parameter" "-Wno-unused-parameter"
"-Wno-psabi" "-Wno-psabi"
"-Wshadow=local"
"-Wduplicated-cond" # check for duplicate conditions "-Wduplicated-cond" # check for duplicate conditions
"-Wduplicated-branches" # check for duplicate branches "-Wduplicated-branches" # check for duplicate branches
"-Wlogical-op" # Search for bitwise operations instead of logical "-Wlogical-op" # Search for bitwise operations instead of logical

View File

@ -1,7 +1,7 @@
/** /**
* @brief Auto-generated event translation file. Contains 256 translations. * @brief Auto-generated event translation file. Contains 257 translations.
* @details * @details
* Generated on: 2023-02-13 10:07:30 * Generated on: 2023-02-17 13:15:51
*/ */
#include "translateEvents.h" #include "translateEvents.h"
@ -92,6 +92,7 @@ const char *MSG_QUEUE_ERROR_STRING = "MSG_QUEUE_ERROR";
const char *SERIALIZATION_ERROR_STRING = "SERIALIZATION_ERROR"; const char *SERIALIZATION_ERROR_STRING = "SERIALIZATION_ERROR";
const char *SAFE_RATE_VIOLATION_STRING = "SAFE_RATE_VIOLATION"; const char *SAFE_RATE_VIOLATION_STRING = "SAFE_RATE_VIOLATION";
const char *SAFE_RATE_RECOVERY_STRING = "SAFE_RATE_RECOVERY"; const char *SAFE_RATE_RECOVERY_STRING = "SAFE_RATE_RECOVERY";
const char *MULTIPLE_RW_INVALID_STRING = "MULTIPLE_RW_INVALID";
const char *SWITCH_CMD_SENT_STRING = "SWITCH_CMD_SENT"; const char *SWITCH_CMD_SENT_STRING = "SWITCH_CMD_SENT";
const char *SWITCH_HAS_CHANGED_STRING = "SWITCH_HAS_CHANGED"; const char *SWITCH_HAS_CHANGED_STRING = "SWITCH_HAS_CHANGED";
const char *SWITCHING_Q7S_DENIED_STRING = "SWITCHING_Q7S_DENIED"; const char *SWITCHING_Q7S_DENIED_STRING = "SWITCHING_Q7S_DENIED";
@ -129,8 +130,8 @@ const char *SELF_TEST_COIL_CURRENT_FAILURE_STRING = "SELF_TEST_COIL_CURRENT_FAIL
const char *INVALID_ERROR_BYTE_STRING = "INVALID_ERROR_BYTE"; const char *INVALID_ERROR_BYTE_STRING = "INVALID_ERROR_BYTE";
const char *ERROR_STATE_STRING = "ERROR_STATE"; const char *ERROR_STATE_STRING = "ERROR_STATE";
const char *RESET_OCCURED_STRING = "RESET_OCCURED"; const char *RESET_OCCURED_STRING = "RESET_OCCURED";
const char *BOOTING_FIRMWARE_FAILED_STRING = "BOOTING_FIRMWARE_FAILED"; const char *BOOTING_FIRMWARE_FAILED_EVENT_STRING = "BOOTING_FIRMWARE_FAILED_EVENT";
const char *BOOTING_BOOTLOADER_FAILED_STRING = "BOOTING_BOOTLOADER_FAILED"; const char *BOOTING_BOOTLOADER_FAILED_EVENT_STRING = "BOOTING_BOOTLOADER_FAILED_EVENT";
const char *SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING = "SUPV_MEMORY_READ_RPT_CRC_FAILURE"; const char *SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING = "SUPV_MEMORY_READ_RPT_CRC_FAILURE";
const char *SUPV_UNKNOWN_TM_STRING = "SUPV_UNKNOWN_TM"; const char *SUPV_UNKNOWN_TM_STRING = "SUPV_UNKNOWN_TM";
const char *SUPV_UNINIMPLEMENTED_TM_STRING = "SUPV_UNINIMPLEMENTED_TM"; const char *SUPV_UNINIMPLEMENTED_TM_STRING = "SUPV_UNINIMPLEMENTED_TM";
@ -433,6 +434,8 @@ const char *translateEvents(Event event) {
return SAFE_RATE_VIOLATION_STRING; return SAFE_RATE_VIOLATION_STRING;
case (11201): case (11201):
return SAFE_RATE_RECOVERY_STRING; return SAFE_RATE_RECOVERY_STRING;
case (11202):
return MULTIPLE_RW_INVALID_STRING;
case (11300): case (11300):
return SWITCH_CMD_SENT_STRING; return SWITCH_CMD_SENT_STRING;
case (11301): case (11301):
@ -508,9 +511,9 @@ const char *translateEvents(Event event) {
case (11802): case (11802):
return RESET_OCCURED_STRING; return RESET_OCCURED_STRING;
case (11901): case (11901):
return BOOTING_FIRMWARE_FAILED_STRING; return BOOTING_FIRMWARE_FAILED_EVENT_STRING;
case (11902): case (11902):
return BOOTING_BOOTLOADER_FAILED_STRING; return BOOTING_BOOTLOADER_FAILED_EVENT_STRING;
case (12001): case (12001):
return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING; return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING;
case (12002): case (12002):

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 13:15:51
*/ */
#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;
@ -139,17 +139,17 @@ ReturnValue_t spiCallback(SpiComIF* comIf, SpiCookie* cookie, const uint8_t* sen
* However, receiving more than 5 empty frames will be interpreted as an error. * However, receiving more than 5 empty frames will be interpreted as an error.
*/ */
uint8_t byteRead = 0; uint8_t byteRead = 0;
for (int idx = 0; idx < 10; idx++) { for (idx = 0; idx < 10; idx++) {
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

@ -160,7 +160,7 @@ ReturnValue_t CoreController::initializeAfterTaskCreation() {
sdcMan->setActiveSdCard(sdInfo.active); sdcMan->setActiveSdCard(sdInfo.active);
currMntPrefix = sdcMan->getCurrentMountPrefix(); currMntPrefix = sdcMan->getCurrentMountPrefix();
if (BLOCKING_SD_INIT) { if (BLOCKING_SD_INIT) {
ReturnValue_t result = initSdCardBlocking(); result = initSdCardBlocking();
if (result != returnvalue::OK and result != SdCardManager::ALREADY_MOUNTED) { if (result != returnvalue::OK and result != SdCardManager::ALREADY_MOUNTED) {
sif::warning << "CoreController::CoreController: SD card init failed" << std::endl; sif::warning << "CoreController::CoreController: SD card init failed" << std::endl;
} }
@ -1163,7 +1163,7 @@ ReturnValue_t CoreController::updateProtInfo(bool regenerateChipStateFile) {
uint8_t lineCounter = 0; uint8_t lineCounter = 0;
string word; string word;
while (getline(chipStateFile, nextLine)) { while (getline(chipStateFile, nextLine)) {
ReturnValue_t result = handleProtInfoUpdateLine(nextLine); result = handleProtInfoUpdateLine(nextLine);
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
sif::warning << "CoreController::updateProtInfo: Protection info update failed!" << std::endl; sif::warning << "CoreController::updateProtInfo: Protection info update failed!" << std::endl;
return result; return result;

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], idx);
rwCookies[idx]->setCallbackArgs(rwHandler);
#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

@ -25,8 +25,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

@ -1,3 +1,6 @@
#!/bin/bash #!/bin/bash
root="$(pwd)"
ln -s "$root/hooks" "$root/.git/hooks"
git submodule update --init fsfw thirdparty/rapidcsv thirdparty/lwgps thirdparty/json git submodule update --init fsfw thirdparty/rapidcsv thirdparty/lwgps thirdparty/json

View File

@ -61,6 +61,7 @@ static constexpr uint32_t SCHED_BLOCK_1_SUS_READ_MS = 15;
static constexpr uint32_t SCHED_BLOCK_2_SENSOR_READ_MS = 30; static constexpr uint32_t SCHED_BLOCK_2_SENSOR_READ_MS = 30;
static constexpr uint32_t SCHED_BLOCK_3_ACS_CTRL_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_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_SUS_READ_MS) / 400.0; static constexpr float SCHED_BLOCK_1_PERIOD = static_cast<float>(SCHED_BLOCK_1_SUS_READ_MS) / 400.0;
@ -68,6 +69,7 @@ static constexpr float SCHED_BLOCK_2_PERIOD =
static_cast<float>(SCHED_BLOCK_2_SENSOR_READ_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_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_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 9de6c4b3aa20ee63c28051d486be8a12df147f22 Subproject commit c8469ca6473f64676e007e2e2f1c733fe6252053

View File

@ -86,6 +86,7 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path
10802;0x2a32;SERIALIZATION_ERROR;LOW;;fsfw/src/fsfw/cfdp/handler/defs.h 10802;0x2a32;SERIALIZATION_ERROR;LOW;;fsfw/src/fsfw/cfdp/handler/defs.h
11200;0x2bc0;SAFE_RATE_VIOLATION;MEDIUM;;mission/acsDefs.h 11200;0x2bc0;SAFE_RATE_VIOLATION;MEDIUM;;mission/acsDefs.h
11201;0x2bc1;SAFE_RATE_RECOVERY;MEDIUM;;mission/acsDefs.h 11201;0x2bc1;SAFE_RATE_RECOVERY;MEDIUM;;mission/acsDefs.h
11202;0x2bc2;MULTIPLE_RW_INVALID;HIGH;;mission/acsDefs.h
11300;0x2c24;SWITCH_CMD_SENT;INFO;Indicates that a FSFW object requested setting a switch P1: 1 if on was requested, 0 for off | P2: Switch Index;mission/devices/devicedefinitions/powerDefinitions.h 11300;0x2c24;SWITCH_CMD_SENT;INFO;Indicates that a FSFW object requested setting a switch P1: 1 if on was requested, 0 for off | P2: Switch Index;mission/devices/devicedefinitions/powerDefinitions.h
11301;0x2c25;SWITCH_HAS_CHANGED;INFO;Indicated that a switch state has changed P1: New switch state, 1 for on, 0 for off | P2: Switch Index;mission/devices/devicedefinitions/powerDefinitions.h 11301;0x2c25;SWITCH_HAS_CHANGED;INFO;Indicated that a switch state has changed P1: New switch state, 1 for on, 0 for off | P2: Switch Index;mission/devices/devicedefinitions/powerDefinitions.h
11302;0x2c26;SWITCHING_Q7S_DENIED;MEDIUM;;mission/devices/devicedefinitions/powerDefinitions.h 11302;0x2c26;SWITCHING_Q7S_DENIED;MEDIUM;;mission/devices/devicedefinitions/powerDefinitions.h
@ -121,10 +122,10 @@ 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_EVENT;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_EVENT;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
12002;0x2ee2;SUPV_UNKNOWN_TM;LOW;Unhandled event. P1: APID, P2: Service ID;linux/devices/ploc/PlocSupervisorHandler.h 12002;0x2ee2;SUPV_UNKNOWN_TM;LOW;Unhandled event. P1: APID, P2: Service ID;linux/devices/ploc/PlocSupervisorHandler.h
12003;0x2ee3;SUPV_UNINIMPLEMENTED_TM;LOW;;linux/devices/ploc/PlocSupervisorHandler.h 12003;0x2ee3;SUPV_UNINIMPLEMENTED_TM;LOW;;linux/devices/ploc/PlocSupervisorHandler.h

1 Event ID (dec) Event ID (hex) Name Severity Description File Path
86 10802 0x2a32 SERIALIZATION_ERROR LOW fsfw/src/fsfw/cfdp/handler/defs.h
87 11200 0x2bc0 SAFE_RATE_VIOLATION MEDIUM mission/acsDefs.h
88 11201 0x2bc1 SAFE_RATE_RECOVERY MEDIUM mission/acsDefs.h
89 11202 0x2bc2 MULTIPLE_RW_INVALID HIGH mission/acsDefs.h
90 11300 0x2c24 SWITCH_CMD_SENT INFO Indicates that a FSFW object requested setting a switch P1: 1 if on was requested, 0 for off | P2: Switch Index mission/devices/devicedefinitions/powerDefinitions.h
91 11301 0x2c25 SWITCH_HAS_CHANGED INFO Indicated that a switch state has changed P1: New switch state, 1 for on, 0 for off | P2: Switch Index mission/devices/devicedefinitions/powerDefinitions.h
92 11302 0x2c26 SWITCHING_Q7S_DENIED MEDIUM mission/devices/devicedefinitions/powerDefinitions.h
122 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
123 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
124 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
125 11801 0x2e19 ERROR_STATE HIGH Reaction wheel signals an error state mission/devices/devicedefinitions/RwDefinitions.h mission/devices/devicedefinitions/rwHelpers.h
126 11802 0x2e1a RESET_OCCURED LOW mission/devices/devicedefinitions/RwDefinitions.h mission/devices/devicedefinitions/rwHelpers.h
127 11901 0x2e7d BOOTING_FIRMWARE_FAILED BOOTING_FIRMWARE_FAILED_EVENT LOW Failed to boot firmware linux/devices/startracker/StarTrackerHandler.h
128 11902 0x2e7e BOOTING_BOOTLOADER_FAILED BOOTING_BOOTLOADER_FAILED_EVENT LOW Failed to boot star tracker into bootloader mode linux/devices/startracker/StarTrackerHandler.h
129 12001 0x2ee1 SUPV_MEMORY_READ_RPT_CRC_FAILURE LOW PLOC supervisor crc failure in telemetry packet linux/devices/ploc/PlocSupervisorHandler.h
130 12002 0x2ee2 SUPV_UNKNOWN_TM LOW Unhandled event. P1: APID, P2: Service ID linux/devices/ploc/PlocSupervisorHandler.h
131 12003 0x2ee3 SUPV_UNINIMPLEMENTED_TM LOW linux/devices/ploc/PlocSupervisorHandler.h

View File

@ -2,24 +2,26 @@ 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 0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h
0x52b0;RWHA_SpiWriteFailure;;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
0x5d00;GOMS_PacketTooLong;;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x5d00;GOMS_PacketTooLong;;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x5d01;GOMS_InvalidTableId;;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x5d01;GOMS_InvalidTableId;;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x5d02;GOMS_InvalidAddress;;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x5d02;GOMS_InvalidAddress;;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x5d03;GOMS_InvalidParamSize;;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x5d03;GOMS_InvalidParamSize;;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x5d04;GOMS_InvalidPayloadSize;;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x5d04;GOMS_InvalidPayloadSize;;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x5d05;GOMS_UnknownReplyId;;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x5d05;GOMS_UnknownReplyId;;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x52b0;RWHA_SpiWriteFailure;;176;RW_HANDLER;mission/devices/RwHandler.h 0x5da0;GOMS_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
0x52b1;RWHA_SpiReadFailure;Used by the spi send function to tell a failing read call;177;RW_HANDLER;mission/devices/RwHandler.h 0x5da1;GOMS_InvalidRampTime;Action Message with invalid ramp time was received.;161;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
0x52b2;RWHA_MissingStartSign;Can be used by the HDLC decoding mechanism to inform about a missing start sign 0x7E;178;RW_HANDLER;mission/devices/RwHandler.h 0x5da2;GOMS_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
0x52b3;RWHA_InvalidSubstitute;Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination;179;RW_HANDLER;mission/devices/RwHandler.h 0x5da3;GOMS_ExecutionFailed;Command execution failed;163;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
0x52b4;RWHA_MissingEndSign;HDLC decoding mechanism never receives the end sign 0x7E;180;RW_HANDLER;mission/devices/RwHandler.h 0x5da4;GOMS_CrcError;Reaction wheel reply has invalid crc;164;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
0x52b5;RWHA_NoReply;Reaction wheel only responds with empty frames.;181;RW_HANDLER;mission/devices/RwHandler.h 0x5da5;GOMS_ValueNotRead;;165;GOM_SPACE_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 0x4fa1;HEATER_CommandNotSupported;;161;HEATER_HANDLER;mission/devices/HeaterHandler.h
0x4fa2;HEATER_InitFailed;;162;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 0x4fa3;HEATER_InvalidSwitchNr;;163;HEATER_HANDLER;mission/devices/HeaterHandler.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 CCSDS_CommandNotImplemented Received action message with unknown action id 160 CCSDS_HANDLER mission/tmtc/CcsdsIpCoreHandler.h
5 0x52b0 RWHA_SpiWriteFailure 176 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
6 0x52b1 RWHA_SpiReadFailure Used by the spi send function to tell a failing read call 177 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
7 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
8 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
9 0x52b4 RWHA_MissingEndSign HDLC decoding mechanism never receives the end sign 0x7E 180 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
10 0x52b5 RWHA_NoReply Reaction wheel only responds with empty frames. 181 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
11 0x52b6 RWHA_NoStartMarker Expected a start marker as first byte 182 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
12 0x52b7 RWHA_SpiReadTimeout Timeout when reading reply 183 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
13 0x5d00 GOMS_PacketTooLong 0 GOM_SPACE_HANDLER mission/devices/GomspaceDeviceHandler.h
14 0x5d01 GOMS_InvalidTableId 1 GOM_SPACE_HANDLER mission/devices/GomspaceDeviceHandler.h
15 0x5d02 GOMS_InvalidAddress 2 GOM_SPACE_HANDLER mission/devices/GomspaceDeviceHandler.h
16 0x5d03 GOMS_InvalidParamSize 3 GOM_SPACE_HANDLER mission/devices/GomspaceDeviceHandler.h
17 0x5d04 GOMS_InvalidPayloadSize 4 GOM_SPACE_HANDLER mission/devices/GomspaceDeviceHandler.h
18 0x5d05 GOMS_UnknownReplyId 5 GOM_SPACE_HANDLER mission/devices/GomspaceDeviceHandler.h
19 0x52b0 0x5da0 RWHA_SpiWriteFailure GOMS_InvalidSpeed Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000] 176 160 RW_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h
20 0x52b1 0x5da1 RWHA_SpiReadFailure GOMS_InvalidRampTime Used by the spi send function to tell a failing read call Action Message with invalid ramp time was received. 177 161 RW_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h
21 0x52b2 0x5da2 RWHA_MissingStartSign GOMS_SetSpeedCommandInvalidLength Can be used by the HDLC decoding mechanism to inform about a missing start sign 0x7E Received set speed command has invalid length. Should be 6. 178 162 RW_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h
22 0x52b3 0x5da3 RWHA_InvalidSubstitute GOMS_ExecutionFailed Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination Command execution failed 179 163 RW_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h
23 0x52b4 0x5da4 RWHA_MissingEndSign GOMS_CrcError HDLC decoding mechanism never receives the end sign 0x7E Reaction wheel reply has invalid crc 180 164 RW_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h
24 0x52b5 0x5da5 RWHA_NoReply GOMS_ValueNotRead Reaction wheel only responds with empty frames. 181 165 RW_HANDLER GOM_SPACE_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
25 0x4fa1 HEATER_CommandNotSupported 161 HEATER_HANDLER mission/devices/HeaterHandler.h
26 0x4fa2 HEATER_InitFailed 162 HEATER_HANDLER mission/devices/HeaterHandler.h
27 0x4fa3 HEATER_InvalidSwitchNr 163 HEATER_HANDLER mission/devices/HeaterHandler.h

View File

@ -86,6 +86,7 @@ Event ID (dec); Event ID (hex); Name; Severity; Description; File Path
10802;0x2a32;SERIALIZATION_ERROR;LOW;;fsfw/src/fsfw/cfdp/handler/defs.h 10802;0x2a32;SERIALIZATION_ERROR;LOW;;fsfw/src/fsfw/cfdp/handler/defs.h
11200;0x2bc0;SAFE_RATE_VIOLATION;MEDIUM;;mission/acsDefs.h 11200;0x2bc0;SAFE_RATE_VIOLATION;MEDIUM;;mission/acsDefs.h
11201;0x2bc1;SAFE_RATE_RECOVERY;MEDIUM;;mission/acsDefs.h 11201;0x2bc1;SAFE_RATE_RECOVERY;MEDIUM;;mission/acsDefs.h
11202;0x2bc2;MULTIPLE_RW_INVALID;HIGH;;mission/acsDefs.h
11300;0x2c24;SWITCH_CMD_SENT;INFO;Indicates that a FSFW object requested setting a switch P1: 1 if on was requested, 0 for off | P2: Switch Index;mission/devices/devicedefinitions/powerDefinitions.h 11300;0x2c24;SWITCH_CMD_SENT;INFO;Indicates that a FSFW object requested setting a switch P1: 1 if on was requested, 0 for off | P2: Switch Index;mission/devices/devicedefinitions/powerDefinitions.h
11301;0x2c25;SWITCH_HAS_CHANGED;INFO;Indicated that a switch state has changed P1: New switch state, 1 for on, 0 for off | P2: Switch Index;mission/devices/devicedefinitions/powerDefinitions.h 11301;0x2c25;SWITCH_HAS_CHANGED;INFO;Indicated that a switch state has changed P1: New switch state, 1 for on, 0 for off | P2: Switch Index;mission/devices/devicedefinitions/powerDefinitions.h
11302;0x2c26;SWITCHING_Q7S_DENIED;MEDIUM;;mission/devices/devicedefinitions/powerDefinitions.h 11302;0x2c26;SWITCHING_Q7S_DENIED;MEDIUM;;mission/devices/devicedefinitions/powerDefinitions.h
@ -121,10 +122,10 @@ 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_EVENT;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_EVENT;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
12002;0x2ee2;SUPV_UNKNOWN_TM;LOW;Unhandled event. P1: APID, P2: Service ID;linux/devices/ploc/PlocSupervisorHandler.h 12002;0x2ee2;SUPV_UNKNOWN_TM;LOW;Unhandled event. P1: APID, P2: Service ID;linux/devices/ploc/PlocSupervisorHandler.h
12003;0x2ee3;SUPV_UNINIMPLEMENTED_TM;LOW;;linux/devices/ploc/PlocSupervisorHandler.h 12003;0x2ee3;SUPV_UNINIMPLEMENTED_TM;LOW;;linux/devices/ploc/PlocSupervisorHandler.h

1 Event ID (dec) Event ID (hex) Name Severity Description File Path
86 10802 0x2a32 SERIALIZATION_ERROR LOW fsfw/src/fsfw/cfdp/handler/defs.h
87 11200 0x2bc0 SAFE_RATE_VIOLATION MEDIUM mission/acsDefs.h
88 11201 0x2bc1 SAFE_RATE_RECOVERY MEDIUM mission/acsDefs.h
89 11202 0x2bc2 MULTIPLE_RW_INVALID HIGH mission/acsDefs.h
90 11300 0x2c24 SWITCH_CMD_SENT INFO Indicates that a FSFW object requested setting a switch P1: 1 if on was requested, 0 for off | P2: Switch Index mission/devices/devicedefinitions/powerDefinitions.h
91 11301 0x2c25 SWITCH_HAS_CHANGED INFO Indicated that a switch state has changed P1: New switch state, 1 for on, 0 for off | P2: Switch Index mission/devices/devicedefinitions/powerDefinitions.h
92 11302 0x2c26 SWITCHING_Q7S_DENIED MEDIUM mission/devices/devicedefinitions/powerDefinitions.h
122 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
123 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
124 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
125 11801 0x2e19 ERROR_STATE HIGH Reaction wheel signals an error state mission/devices/devicedefinitions/RwDefinitions.h mission/devices/devicedefinitions/rwHelpers.h
126 11802 0x2e1a RESET_OCCURED LOW mission/devices/devicedefinitions/RwDefinitions.h mission/devices/devicedefinitions/rwHelpers.h
127 11901 0x2e7d BOOTING_FIRMWARE_FAILED BOOTING_FIRMWARE_FAILED_EVENT LOW Failed to boot firmware linux/devices/startracker/StarTrackerHandler.h
128 11902 0x2e7e BOOTING_BOOTLOADER_FAILED BOOTING_BOOTLOADER_FAILED_EVENT LOW Failed to boot star tracker into bootloader mode linux/devices/startracker/StarTrackerHandler.h
129 12001 0x2ee1 SUPV_MEMORY_READ_RPT_CRC_FAILURE LOW PLOC supervisor crc failure in telemetry packet linux/devices/ploc/PlocSupervisorHandler.h
130 12002 0x2ee2 SUPV_UNKNOWN_TM LOW Unhandled event. P1: APID, P2: Service ID linux/devices/ploc/PlocSupervisorHandler.h
131 12003 0x2ee3 SUPV_UNINIMPLEMENTED_TM LOW 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 0x49010005 GPIO_IF
77 0x49010006 SCEX_UART_READER
78 0x49020004 SPI_MAIN_COM_IF
79 0x49020005 SPI_RW_COM_IF RW_POLLING_TASK
80 0x49020006 SPI_RTD_COM_IF
81 0x49030003 UART_COM_IF
82 0x49040002 I2C_COM_IF

View File

@ -2,24 +2,26 @@ 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 0x60a0;CCSDS_CommandNotImplemented;Received action message with unknown action id;160;CCSDS_HANDLER;mission/tmtc/CcsdsIpCoreHandler.h
0x52b0;RWHA_SpiWriteFailure;;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
0x5d00;GOMS_PacketTooLong;;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x5d00;GOMS_PacketTooLong;;0;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x5d01;GOMS_InvalidTableId;;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x5d01;GOMS_InvalidTableId;;1;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x5d02;GOMS_InvalidAddress;;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x5d02;GOMS_InvalidAddress;;2;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x5d03;GOMS_InvalidParamSize;;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x5d03;GOMS_InvalidParamSize;;3;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x5d04;GOMS_InvalidPayloadSize;;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x5d04;GOMS_InvalidPayloadSize;;4;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x5d05;GOMS_UnknownReplyId;;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h 0x5d05;GOMS_UnknownReplyId;;5;GOM_SPACE_HANDLER;mission/devices/GomspaceDeviceHandler.h
0x52b0;RWHA_SpiWriteFailure;;176;RW_HANDLER;mission/devices/RwHandler.h 0x5da0;GOMS_InvalidSpeed;Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000];160;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
0x52b1;RWHA_SpiReadFailure;Used by the spi send function to tell a failing read call;177;RW_HANDLER;mission/devices/RwHandler.h 0x5da1;GOMS_InvalidRampTime;Action Message with invalid ramp time was received.;161;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
0x52b2;RWHA_MissingStartSign;Can be used by the HDLC decoding mechanism to inform about a missing start sign 0x7E;178;RW_HANDLER;mission/devices/RwHandler.h 0x5da2;GOMS_SetSpeedCommandInvalidLength;Received set speed command has invalid length. Should be 6.;162;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
0x52b3;RWHA_InvalidSubstitute;Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination;179;RW_HANDLER;mission/devices/RwHandler.h 0x5da3;GOMS_ExecutionFailed;Command execution failed;163;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
0x52b4;RWHA_MissingEndSign;HDLC decoding mechanism never receives the end sign 0x7E;180;RW_HANDLER;mission/devices/RwHandler.h 0x5da4;GOMS_CrcError;Reaction wheel reply has invalid crc;164;GOM_SPACE_HANDLER;mission/devices/RwHandler.h
0x52b5;RWHA_NoReply;Reaction wheel only responds with empty frames.;181;RW_HANDLER;mission/devices/RwHandler.h 0x5da5;GOMS_ValueNotRead;;165;GOM_SPACE_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 0x4fa1;HEATER_CommandNotSupported;;161;HEATER_HANDLER;mission/devices/HeaterHandler.h
0x4fa2;HEATER_InitFailed;;162;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 0x4fa3;HEATER_InvalidSwitchNr;;163;HEATER_HANDLER;mission/devices/HeaterHandler.h
@ -573,20 +575,20 @@ Full ID (hex); Name; Description; Unique ID; Subsytem Name; File Path
0x5402;DWLPWRON_InvalidCrc;;2;DWLPWRON_CMD;linux/devices/ScexHelper.h 0x5402;DWLPWRON_InvalidCrc;;2;DWLPWRON_CMD;linux/devices/ScexHelper.h
0x59a0;IPCI_PapbBusy;;160;CCSDS_IP_CORE_BRIDGE;linux/ipcore/PapbVcInterface.h 0x59a0;IPCI_PapbBusy;;160;CCSDS_IP_CORE_BRIDGE;linux/ipcore/PapbVcInterface.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_AbandonedCltuRetval;;160;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fa1;PDEC_FrameDirty;;161;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fa1;PDEC_FrameDirtyRetval;;161;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fa2;PDEC_FrameIllegalMultipleReasons;;162;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fa2;PDEC_FrameIllegalMultipleReasons;;162;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fa3;PDEC_AdDiscardedLockout;;163;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fa3;PDEC_AdDiscardedLockoutRetval;;163;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fa4;PDEC_AdDiscardedWait;;164;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fa4;PDEC_AdDiscardedWaitRetval;;164;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fa5;PDEC_AdDiscardedNsVs;;165;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fa5;PDEC_AdDiscardedNsVs;;165;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fb0;PDEC_CommandNotImplemented;Received action message with unknown action id;176;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fb0;PDEC_CommandNotImplemented;Received action message with unknown action id;176;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fa6;PDEC_NoReport;;166;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fa6;PDEC_NoReportRetval;;166;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fa7;PDEC_ErrorVersionNumber;;167;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fa7;PDEC_ErrorVersionNumberRetval;;167;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fa8;PDEC_IllegalCombination;;168;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fa8;PDEC_IllegalCombinationRetval;;168;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fa9;PDEC_InvalidScId;;169;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fa9;PDEC_InvalidScIdRetval;;169;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5faa;PDEC_InvalidVcIdMsb;;170;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5faa;PDEC_InvalidVcIdMsbRetval;;170;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fab;PDEC_InvalidVcIdLsb;;171;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fab;PDEC_InvalidVcIdLsbRetval;;171;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fac;PDEC_NsNotZero;;172;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fac;PDEC_NsNotZeroRetval;;172;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x5fae;PDEC_InvalidBcCc;;174;PDEC_HANDLER;linux/ipcore/PdecHandler.h 0x5fae;PDEC_InvalidBcCc;;174;PDEC_HANDLER;linux/ipcore/PdecHandler.h
0x61a0;RS_RateNotSupported;The commanded rate is not supported by the current FPGA design;160;RATE_SETTER;linux/ipcore/PtmeConfig.h 0x61a0;RS_RateNotSupported;The commanded rate is not supported by the current FPGA design;160;RATE_SETTER;linux/ipcore/PtmeConfig.h
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

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 CCSDS_CommandNotImplemented Received action message with unknown action id 160 CCSDS_HANDLER mission/tmtc/CcsdsIpCoreHandler.h
5 0x52b0 RWHA_SpiWriteFailure 176 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
6 0x52b1 RWHA_SpiReadFailure Used by the spi send function to tell a failing read call 177 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
7 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
8 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
9 0x52b4 RWHA_MissingEndSign HDLC decoding mechanism never receives the end sign 0x7E 180 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
10 0x52b5 RWHA_NoReply Reaction wheel only responds with empty frames. 181 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
11 0x52b6 RWHA_NoStartMarker Expected a start marker as first byte 182 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
12 0x52b7 RWHA_SpiReadTimeout Timeout when reading reply 183 RW_HANDLER mission/devices/devicedefinitions/rwHelpers.h
13 0x5d00 GOMS_PacketTooLong 0 GOM_SPACE_HANDLER mission/devices/GomspaceDeviceHandler.h
14 0x5d01 GOMS_InvalidTableId 1 GOM_SPACE_HANDLER mission/devices/GomspaceDeviceHandler.h
15 0x5d02 GOMS_InvalidAddress 2 GOM_SPACE_HANDLER mission/devices/GomspaceDeviceHandler.h
16 0x5d03 GOMS_InvalidParamSize 3 GOM_SPACE_HANDLER mission/devices/GomspaceDeviceHandler.h
17 0x5d04 GOMS_InvalidPayloadSize 4 GOM_SPACE_HANDLER mission/devices/GomspaceDeviceHandler.h
18 0x5d05 GOMS_UnknownReplyId 5 GOM_SPACE_HANDLER mission/devices/GomspaceDeviceHandler.h
19 0x52b0 0x5da0 RWHA_SpiWriteFailure GOMS_InvalidSpeed Action Message with invalid speed was received. Valid speeds must be in the range of [-65000, 1000] or [1000, 65000] 176 160 RW_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h
20 0x52b1 0x5da1 RWHA_SpiReadFailure GOMS_InvalidRampTime Used by the spi send function to tell a failing read call Action Message with invalid ramp time was received. 177 161 RW_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h
21 0x52b2 0x5da2 RWHA_MissingStartSign GOMS_SetSpeedCommandInvalidLength Can be used by the HDLC decoding mechanism to inform about a missing start sign 0x7E Received set speed command has invalid length. Should be 6. 178 162 RW_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h
22 0x52b3 0x5da3 RWHA_InvalidSubstitute GOMS_ExecutionFailed Can be used by the HDLC decoding mechanism to inform about an invalid substitution combination Command execution failed 179 163 RW_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h
23 0x52b4 0x5da4 RWHA_MissingEndSign GOMS_CrcError HDLC decoding mechanism never receives the end sign 0x7E Reaction wheel reply has invalid crc 180 164 RW_HANDLER GOM_SPACE_HANDLER mission/devices/RwHandler.h
24 0x52b5 0x5da5 RWHA_NoReply GOMS_ValueNotRead Reaction wheel only responds with empty frames. 181 165 RW_HANDLER GOM_SPACE_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
25 0x4fa1 HEATER_CommandNotSupported 161 HEATER_HANDLER mission/devices/HeaterHandler.h
26 0x4fa2 HEATER_InitFailed 162 HEATER_HANDLER mission/devices/HeaterHandler.h
27 0x4fa3 HEATER_InvalidSwitchNr 163 HEATER_HANDLER mission/devices/HeaterHandler.h
575 0x5402 DWLPWRON_InvalidCrc 2 DWLPWRON_CMD linux/devices/ScexHelper.h
576 0x59a0 IPCI_PapbBusy 160 CCSDS_IP_CORE_BRIDGE linux/ipcore/PapbVcInterface.h
577 0x5aa0 PTME_UnknownVcId 160 PTME linux/ipcore/Ptme.h
578 0x5fa0 PDEC_AbandonedCltu PDEC_AbandonedCltuRetval 160 PDEC_HANDLER linux/ipcore/PdecHandler.h
579 0x5fa1 PDEC_FrameDirty PDEC_FrameDirtyRetval 161 PDEC_HANDLER linux/ipcore/PdecHandler.h
580 0x5fa2 PDEC_FrameIllegalMultipleReasons 162 PDEC_HANDLER linux/ipcore/PdecHandler.h
581 0x5fa3 PDEC_AdDiscardedLockout PDEC_AdDiscardedLockoutRetval 163 PDEC_HANDLER linux/ipcore/PdecHandler.h
582 0x5fa4 PDEC_AdDiscardedWait PDEC_AdDiscardedWaitRetval 164 PDEC_HANDLER linux/ipcore/PdecHandler.h
583 0x5fa5 PDEC_AdDiscardedNsVs 165 PDEC_HANDLER linux/ipcore/PdecHandler.h
584 0x5fb0 PDEC_CommandNotImplemented Received action message with unknown action id 176 PDEC_HANDLER linux/ipcore/PdecHandler.h
585 0x5fa6 PDEC_NoReport PDEC_NoReportRetval 166 PDEC_HANDLER linux/ipcore/PdecHandler.h
586 0x5fa7 PDEC_ErrorVersionNumber PDEC_ErrorVersionNumberRetval 167 PDEC_HANDLER linux/ipcore/PdecHandler.h
587 0x5fa8 PDEC_IllegalCombination PDEC_IllegalCombinationRetval 168 PDEC_HANDLER linux/ipcore/PdecHandler.h
588 0x5fa9 PDEC_InvalidScId PDEC_InvalidScIdRetval 169 PDEC_HANDLER linux/ipcore/PdecHandler.h
589 0x5faa PDEC_InvalidVcIdMsb PDEC_InvalidVcIdMsbRetval 170 PDEC_HANDLER linux/ipcore/PdecHandler.h
590 0x5fab PDEC_InvalidVcIdLsb PDEC_InvalidVcIdLsbRetval 171 PDEC_HANDLER linux/ipcore/PdecHandler.h
591 0x5fac PDEC_NsNotZero PDEC_NsNotZeroRetval 172 PDEC_HANDLER linux/ipcore/PdecHandler.h
592 0x5fae PDEC_InvalidBcCc 174 PDEC_HANDLER linux/ipcore/PdecHandler.h
593 0x61a0 RS_RateNotSupported The commanded rate is not supported by the current FPGA design 160 RATE_SETTER linux/ipcore/PtmeConfig.h
594 0x61a1 RS_BadBitRate Bad bitrate has been commanded (e.g. 0) 161 RATE_SETTER linux/ipcore/PtmeConfig.h

View File

@ -1,7 +1,7 @@
/** /**
* @brief Auto-generated event translation file. Contains 256 translations. * @brief Auto-generated event translation file. Contains 257 translations.
* @details * @details
* Generated on: 2023-02-13 10:07:30 * Generated on: 2023-02-17 13:15:51
*/ */
#include "translateEvents.h" #include "translateEvents.h"
@ -92,6 +92,7 @@ const char *MSG_QUEUE_ERROR_STRING = "MSG_QUEUE_ERROR";
const char *SERIALIZATION_ERROR_STRING = "SERIALIZATION_ERROR"; const char *SERIALIZATION_ERROR_STRING = "SERIALIZATION_ERROR";
const char *SAFE_RATE_VIOLATION_STRING = "SAFE_RATE_VIOLATION"; const char *SAFE_RATE_VIOLATION_STRING = "SAFE_RATE_VIOLATION";
const char *SAFE_RATE_RECOVERY_STRING = "SAFE_RATE_RECOVERY"; const char *SAFE_RATE_RECOVERY_STRING = "SAFE_RATE_RECOVERY";
const char *MULTIPLE_RW_INVALID_STRING = "MULTIPLE_RW_INVALID";
const char *SWITCH_CMD_SENT_STRING = "SWITCH_CMD_SENT"; const char *SWITCH_CMD_SENT_STRING = "SWITCH_CMD_SENT";
const char *SWITCH_HAS_CHANGED_STRING = "SWITCH_HAS_CHANGED"; const char *SWITCH_HAS_CHANGED_STRING = "SWITCH_HAS_CHANGED";
const char *SWITCHING_Q7S_DENIED_STRING = "SWITCHING_Q7S_DENIED"; const char *SWITCHING_Q7S_DENIED_STRING = "SWITCHING_Q7S_DENIED";
@ -129,8 +130,8 @@ const char *SELF_TEST_COIL_CURRENT_FAILURE_STRING = "SELF_TEST_COIL_CURRENT_FAIL
const char *INVALID_ERROR_BYTE_STRING = "INVALID_ERROR_BYTE"; const char *INVALID_ERROR_BYTE_STRING = "INVALID_ERROR_BYTE";
const char *ERROR_STATE_STRING = "ERROR_STATE"; const char *ERROR_STATE_STRING = "ERROR_STATE";
const char *RESET_OCCURED_STRING = "RESET_OCCURED"; const char *RESET_OCCURED_STRING = "RESET_OCCURED";
const char *BOOTING_FIRMWARE_FAILED_STRING = "BOOTING_FIRMWARE_FAILED"; const char *BOOTING_FIRMWARE_FAILED_EVENT_STRING = "BOOTING_FIRMWARE_FAILED_EVENT";
const char *BOOTING_BOOTLOADER_FAILED_STRING = "BOOTING_BOOTLOADER_FAILED"; const char *BOOTING_BOOTLOADER_FAILED_EVENT_STRING = "BOOTING_BOOTLOADER_FAILED_EVENT";
const char *SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING = "SUPV_MEMORY_READ_RPT_CRC_FAILURE"; const char *SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING = "SUPV_MEMORY_READ_RPT_CRC_FAILURE";
const char *SUPV_UNKNOWN_TM_STRING = "SUPV_UNKNOWN_TM"; const char *SUPV_UNKNOWN_TM_STRING = "SUPV_UNKNOWN_TM";
const char *SUPV_UNINIMPLEMENTED_TM_STRING = "SUPV_UNINIMPLEMENTED_TM"; const char *SUPV_UNINIMPLEMENTED_TM_STRING = "SUPV_UNINIMPLEMENTED_TM";
@ -433,6 +434,8 @@ const char *translateEvents(Event event) {
return SAFE_RATE_VIOLATION_STRING; return SAFE_RATE_VIOLATION_STRING;
case (11201): case (11201):
return SAFE_RATE_RECOVERY_STRING; return SAFE_RATE_RECOVERY_STRING;
case (11202):
return MULTIPLE_RW_INVALID_STRING;
case (11300): case (11300):
return SWITCH_CMD_SENT_STRING; return SWITCH_CMD_SENT_STRING;
case (11301): case (11301):
@ -508,9 +511,9 @@ const char *translateEvents(Event event) {
case (11802): case (11802):
return RESET_OCCURED_STRING; return RESET_OCCURED_STRING;
case (11901): case (11901):
return BOOTING_FIRMWARE_FAILED_STRING; return BOOTING_FIRMWARE_FAILED_EVENT_STRING;
case (11902): case (11902):
return BOOTING_BOOTLOADER_FAILED_STRING; return BOOTING_BOOTLOADER_FAILED_EVENT_STRING;
case (12001): case (12001):
return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING; return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING;
case (12002): case (12002):

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 13:15:51
*/ */
#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:

6
hooks/post-checkout Executable file
View File

@ -0,0 +1,6 @@
#!/bin/bash
#
# update submodules after checkout
git submodule init
git submodule update

View File

@ -29,7 +29,7 @@ ReturnValue_t I2cTestClass::performPeriodicAction() {
void I2cTestClass::battInit() { void I2cTestClass::battInit() {
sif::info << "I2cTestClass: BPX Initialization" << std::endl; sif::info << "I2cTestClass: BPX Initialization" << std::endl;
UnixFileGuard fileHelper(i2cdev, &bpxInfo.fd, O_RDWR, "I2cTestClass::sendMessage"); UnixFileGuard fileHelper(i2cdev, bpxInfo.fd, O_RDWR, "I2cTestClass::sendMessage");
if (fileHelper.getOpenResult() != returnvalue::OK) { if (fileHelper.getOpenResult() != returnvalue::OK) {
sif::error << "Opening I2C device" << i2cdev << " failed" << std::endl; sif::error << "Opening I2C device" << i2cdev << " failed" << std::endl;
return; return;
@ -58,7 +58,7 @@ void I2cTestClass::battInit() {
} }
void I2cTestClass::battPeriodic() { void I2cTestClass::battPeriodic() {
UnixFileGuard fileHelper(i2cdev, &bpxInfo.fd, O_RDWR, "I2cTestClass::sendMessage"); UnixFileGuard fileHelper(i2cdev, bpxInfo.fd, O_RDWR, "I2cTestClass::sendMessage");
if (fileHelper.getOpenResult() != returnvalue::OK) { if (fileHelper.getOpenResult() != returnvalue::OK) {
sif::error << "Opening I2C device" << i2cdev << " failed" << std::endl; sif::error << "Opening I2C device" << i2cdev << " failed" << std::endl;
return; return;

View File

@ -94,7 +94,7 @@ void SpiTestClass::performRm3100Test(uint8_t mgmId) {
#endif #endif
int fileDescriptor = 0; int fileDescriptor = 0;
UnixFileGuard fileHelper(deviceName, &fileDescriptor, O_RDWR, "SpiComIF::initializeInterface"); UnixFileGuard fileHelper(deviceName, fileDescriptor, O_RDWR, "SpiComIF::initializeInterface");
if (fileHelper.getOpenResult()) { if (fileHelper.getOpenResult()) {
sif::error << "SpiTestClass::performRm3100Test: File descriptor could not be opened!" sif::error << "SpiTestClass::performRm3100Test: File descriptor could not be opened!"
<< std::endl; << std::endl;
@ -137,7 +137,7 @@ void SpiTestClass::performRm3100Test(uint8_t mgmId) {
if ((statusReg & 0b1000'0000) == 0) { if ((statusReg & 0b1000'0000) == 0) {
sif::warning << "SpiTestClass::performRm3100Test: Data not ready!" << std::endl; sif::warning << "SpiTestClass::performRm3100Test: Data not ready!" << std::endl;
TaskFactory::delayTask(10); TaskFactory::delayTask(10);
uint8_t statusReg = readRm3100Register(fileDescriptor, currentGpioId, 0x34); statusReg = readRm3100Register(fileDescriptor, currentGpioId, 0x34);
if ((statusReg & 0b1000'0000) == 0) { if ((statusReg & 0b1000'0000) == 0) {
return; return;
} }
@ -191,7 +191,7 @@ void SpiTestClass::performLis3MdlTest(uint8_t lis3Id) {
#endif #endif
int fileDescriptor = 0; int fileDescriptor = 0;
UnixFileGuard fileHelper(deviceName, &fileDescriptor, O_RDWR, "SpiComIF::initializeInterface"); UnixFileGuard fileHelper(deviceName, fileDescriptor, O_RDWR, "SpiComIF::initializeInterface");
if (fileHelper.getOpenResult()) { if (fileHelper.getOpenResult()) {
sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!" sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!"
<< std::endl; << std::endl;
@ -231,7 +231,7 @@ void SpiTestClass::performL3gTest(uint8_t l3gId) {
#endif #endif
int fileDescriptor = 0; int fileDescriptor = 0;
UnixFileGuard fileHelper(deviceName, &fileDescriptor, O_RDWR, "SpiComIF::initializeInterface"); UnixFileGuard fileHelper(deviceName, fileDescriptor, O_RDWR, "SpiComIF::initializeInterface");
if (fileHelper.getOpenResult()) { if (fileHelper.getOpenResult()) {
sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!" sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!"
<< std::endl; << std::endl;
@ -341,7 +341,7 @@ void SpiTestClass::performMax1227Test() {
#elif defined(TE0720_1CFA) #elif defined(TE0720_1CFA)
#endif #endif
int fd = 0; int fd = 0;
UnixFileGuard fileHelper(deviceName, &fd, O_RDWR, "SpiComIF::initializeInterface"); UnixFileGuard fileHelper(deviceName, fd, O_RDWR, "SpiComIF::initializeInterface");
if (fileHelper.getOpenResult()) { if (fileHelper.getOpenResult()) {
sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!" sif::error << "SpiTestClass::performLis3Mdl3100Test: File descriptor could not be opened!"
<< std::endl; << std::endl;

View File

@ -141,7 +141,7 @@ ReturnValue_t CspComIF::sendMessage(CookieIF* cookie, const uint8_t* sendData, s
requestStruct.mem_id = P60PDU_PARAM; requestStruct.mem_id = P60PDU_PARAM;
requestStruct.count = p60pdu_config_count; requestStruct.count = p60pdu_config_count;
requestStruct.size = P60PDU_PARAM_SIZE; requestStruct.size = P60PDU_PARAM_SIZE;
int result = rparam_get_full_table(&requestStruct, cspAddress, P60_PORT_RPARAM, result = rparam_get_full_table(&requestStruct, cspAddress, P60_PORT_RPARAM,
requestStruct.mem_id, cspCookie->getTimeout()); requestStruct.mem_id, cspCookie->getTimeout());
if (result != 0) { if (result != 0) {
return returnvalue::FAILED; return returnvalue::FAILED;
@ -151,7 +151,7 @@ ReturnValue_t CspComIF::sendMessage(CookieIF* cookie, const uint8_t* sendData, s
requestStruct.mem_id = P60ACU_PARAM; requestStruct.mem_id = P60ACU_PARAM;
requestStruct.count = p60acu_config_count; requestStruct.count = p60acu_config_count;
requestStruct.size = P60ACU_PARAM_SIZE; requestStruct.size = P60ACU_PARAM_SIZE;
int result = rparam_get_full_table(&requestStruct, cspAddress, P60_PORT_RPARAM, result = rparam_get_full_table(&requestStruct, cspAddress, P60_PORT_RPARAM,
requestStruct.mem_id, cspCookie->getTimeout()); requestStruct.mem_id, cspCookie->getTimeout());
if (result != 0) { if (result != 0) {
return returnvalue::FAILED; return returnvalue::FAILED;
@ -161,7 +161,7 @@ ReturnValue_t CspComIF::sendMessage(CookieIF* cookie, const uint8_t* sendData, s
requestStruct.mem_id = P60DOCK_PARAM; requestStruct.mem_id = P60DOCK_PARAM;
requestStruct.count = p60dock_config_count; requestStruct.count = p60dock_config_count;
requestStruct.size = P60DOCK_PARAM_SIZE; requestStruct.size = P60DOCK_PARAM_SIZE;
int result = rparam_get_full_table(&requestStruct, cspAddress, P60_PORT_RPARAM, result = rparam_get_full_table(&requestStruct, cspAddress, P60_PORT_RPARAM,
requestStruct.mem_id, cspCookie->getTimeout()); requestStruct.mem_id, cspCookie->getTimeout());
if (result != 0) { if (result != 0) {
return returnvalue::FAILED; return returnvalue::FAILED;
@ -171,7 +171,7 @@ ReturnValue_t CspComIF::sendMessage(CookieIF* cookie, const uint8_t* sendData, s
return returnvalue::FAILED; return returnvalue::FAILED;
} }
const TableInfo* tableInfo = reinterpret_cast<const TableInfo*>(sendData); const TableInfo* tableInfo = reinterpret_cast<const TableInfo*>(sendData);
int result = gs_rparam_save(cspAddress, cspCookie->getTimeout(), tableInfo->sourceTable, result = gs_rparam_save(cspAddress, cspCookie->getTimeout(), tableInfo->sourceTable,
tableInfo->targetTable); tableInfo->targetTable);
if (result != 0) { if (result != 0) {
return returnvalue::FAILED; return returnvalue::FAILED;
@ -181,7 +181,7 @@ ReturnValue_t CspComIF::sendMessage(CookieIF* cookie, const uint8_t* sendData, s
return returnvalue::FAILED; return returnvalue::FAILED;
} }
const TableInfo* tableInfo = reinterpret_cast<const TableInfo*>(sendData); const TableInfo* tableInfo = reinterpret_cast<const TableInfo*>(sendData);
int result = gs_rparam_load(cspAddress, cspCookie->getTimeout(), tableInfo->sourceTable, result = gs_rparam_load(cspAddress, cspCookie->getTimeout(), tableInfo->sourceTable,
tableInfo->targetTable); tableInfo->targetTable);
if (result != 0) { if (result != 0) {
return returnvalue::FAILED; return returnvalue::FAILED;

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

@ -232,7 +232,7 @@ ReturnValue_t Max31865RtdReader::sendMessage(CookieIF* cookie, const uint8_t* se
return returnvalue::FAILED; return returnvalue::FAILED;
} }
auto thresholdHandler = [](Max31865ReaderCookie* rtdCookie, const uint8_t* sendData) { auto thresholdHandler = [&]() {
rtdCookie->lowThreshold = (sendData[1] << 8) | sendData[2]; rtdCookie->lowThreshold = (sendData[1] << 8) | sendData[2];
rtdCookie->highThreshold = (sendData[3] << 8) | sendData[4]; rtdCookie->highThreshold = (sendData[3] << 8) | sendData[4];
rtdCookie->writeLowThreshold = true; rtdCookie->writeLowThreshold = true;
@ -249,7 +249,7 @@ ReturnValue_t Max31865RtdReader::sendMessage(CookieIF* cookie, const uint8_t* se
rtdCookie->db.active = false; rtdCookie->db.active = false;
rtdCookie->db.configured = false; rtdCookie->db.configured = false;
if (sendLen == 5) { if (sendLen == 5) {
thresholdHandler(rtdCookie, sendData); thresholdHandler();
} }
} }
break; break;
@ -265,7 +265,7 @@ ReturnValue_t Max31865RtdReader::sendMessage(CookieIF* cookie, const uint8_t* se
rtdCookie->db.active = true; rtdCookie->db.active = true;
} }
if (sendLen == 5) { if (sendLen == 5) {
thresholdHandler(rtdCookie, sendData); thresholdHandler();
} }
break; break;
} }

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;
}
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) {
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

@ -119,7 +119,7 @@ ReturnValue_t PlocSupervisorHandler::executeAction(ActionId_t actionId,
case MEMORY_CHECK_WITH_FILE: { case MEMORY_CHECK_WITH_FILE: {
shutdownCmdSent = false; shutdownCmdSent = false;
UpdateParams params; UpdateParams params;
ReturnValue_t result = extractBaseParams(&data, size, params); result = extractBaseParams(&data, size, params);
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
return result; return result;
} }

View File

@ -1909,7 +1909,7 @@ ReturnValue_t StarTrackerHandler::checkProgram() {
if (internalState == InternalState::VERIFY_BOOT) { if (internalState == InternalState::VERIFY_BOOT) {
sif::warning << "StarTrackerHandler::checkProgram: Failed to boot firmware" << std::endl; sif::warning << "StarTrackerHandler::checkProgram: Failed to boot firmware" << std::endl;
// Device handler will run into timeout and fall back to transition source mode // Device handler will run into timeout and fall back to transition source mode
triggerEvent(BOOTING_FIRMWARE_FAILED); triggerEvent(BOOTING_FIRMWARE_FAILED_EVENT);
internalState = InternalState::FAILED_FIRMWARE_BOOT; internalState = InternalState::FAILED_FIRMWARE_BOOT;
} else if (internalState == InternalState::BOOTLOADER_CHECK) { } else if (internalState == InternalState::BOOTLOADER_CHECK) {
internalState = InternalState::DONE; internalState = InternalState::DONE;
@ -1922,7 +1922,7 @@ ReturnValue_t StarTrackerHandler::checkProgram() {
if (internalState == InternalState::VERIFY_BOOT) { if (internalState == InternalState::VERIFY_BOOT) {
internalState = InternalState::LOGLEVEL; internalState = InternalState::LOGLEVEL;
} else if (internalState == InternalState::BOOTLOADER_CHECK) { } else if (internalState == InternalState::BOOTLOADER_CHECK) {
triggerEvent(BOOTING_BOOTLOADER_FAILED); triggerEvent(BOOTING_BOOTLOADER_FAILED_EVENT);
internalState = InternalState::BOOTING_BOOTLOADER_FAILED; internalState = InternalState::BOOTING_BOOTLOADER_FAILED;
} }
break; break;

View File

@ -140,9 +140,9 @@ class StarTrackerHandler : public DeviceHandlerBase {
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::STR_HANDLER; static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::STR_HANDLER;
//! [EXPORT] : [COMMENT] Failed to boot firmware //! [EXPORT] : [COMMENT] Failed to boot firmware
static const Event BOOTING_FIRMWARE_FAILED = MAKE_EVENT(1, severity::LOW); static const Event BOOTING_FIRMWARE_FAILED_EVENT = MAKE_EVENT(1, severity::LOW);
//! [EXPORT] : [COMMENT] Failed to boot star tracker into bootloader mode //! [EXPORT] : [COMMENT] Failed to boot star tracker into bootloader mode
static const Event BOOTING_BOOTLOADER_FAILED = MAKE_EVENT(2, severity::LOW); static const Event BOOTING_BOOTLOADER_FAILED_EVENT = MAKE_EVENT(2, severity::LOW);
static const size_t MAX_PATH_SIZE = 50; static const size_t MAX_PATH_SIZE = 50;
static const size_t MAX_FILE_NAME = 30; static const size_t MAX_FILE_NAME = 30;

View File

@ -1,7 +1,7 @@
/** /**
* @brief Auto-generated event translation file. Contains 256 translations. * @brief Auto-generated event translation file. Contains 257 translations.
* @details * @details
* Generated on: 2023-02-13 10:07:30 * Generated on: 2023-02-17 13:15:51
*/ */
#include "translateEvents.h" #include "translateEvents.h"
@ -92,6 +92,7 @@ const char *MSG_QUEUE_ERROR_STRING = "MSG_QUEUE_ERROR";
const char *SERIALIZATION_ERROR_STRING = "SERIALIZATION_ERROR"; const char *SERIALIZATION_ERROR_STRING = "SERIALIZATION_ERROR";
const char *SAFE_RATE_VIOLATION_STRING = "SAFE_RATE_VIOLATION"; const char *SAFE_RATE_VIOLATION_STRING = "SAFE_RATE_VIOLATION";
const char *SAFE_RATE_RECOVERY_STRING = "SAFE_RATE_RECOVERY"; const char *SAFE_RATE_RECOVERY_STRING = "SAFE_RATE_RECOVERY";
const char *MULTIPLE_RW_INVALID_STRING = "MULTIPLE_RW_INVALID";
const char *SWITCH_CMD_SENT_STRING = "SWITCH_CMD_SENT"; const char *SWITCH_CMD_SENT_STRING = "SWITCH_CMD_SENT";
const char *SWITCH_HAS_CHANGED_STRING = "SWITCH_HAS_CHANGED"; const char *SWITCH_HAS_CHANGED_STRING = "SWITCH_HAS_CHANGED";
const char *SWITCHING_Q7S_DENIED_STRING = "SWITCHING_Q7S_DENIED"; const char *SWITCHING_Q7S_DENIED_STRING = "SWITCHING_Q7S_DENIED";
@ -129,8 +130,8 @@ const char *SELF_TEST_COIL_CURRENT_FAILURE_STRING = "SELF_TEST_COIL_CURRENT_FAIL
const char *INVALID_ERROR_BYTE_STRING = "INVALID_ERROR_BYTE"; const char *INVALID_ERROR_BYTE_STRING = "INVALID_ERROR_BYTE";
const char *ERROR_STATE_STRING = "ERROR_STATE"; const char *ERROR_STATE_STRING = "ERROR_STATE";
const char *RESET_OCCURED_STRING = "RESET_OCCURED"; const char *RESET_OCCURED_STRING = "RESET_OCCURED";
const char *BOOTING_FIRMWARE_FAILED_STRING = "BOOTING_FIRMWARE_FAILED"; const char *BOOTING_FIRMWARE_FAILED_EVENT_STRING = "BOOTING_FIRMWARE_FAILED_EVENT";
const char *BOOTING_BOOTLOADER_FAILED_STRING = "BOOTING_BOOTLOADER_FAILED"; const char *BOOTING_BOOTLOADER_FAILED_EVENT_STRING = "BOOTING_BOOTLOADER_FAILED_EVENT";
const char *SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING = "SUPV_MEMORY_READ_RPT_CRC_FAILURE"; const char *SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING = "SUPV_MEMORY_READ_RPT_CRC_FAILURE";
const char *SUPV_UNKNOWN_TM_STRING = "SUPV_UNKNOWN_TM"; const char *SUPV_UNKNOWN_TM_STRING = "SUPV_UNKNOWN_TM";
const char *SUPV_UNINIMPLEMENTED_TM_STRING = "SUPV_UNINIMPLEMENTED_TM"; const char *SUPV_UNINIMPLEMENTED_TM_STRING = "SUPV_UNINIMPLEMENTED_TM";
@ -433,6 +434,8 @@ const char *translateEvents(Event event) {
return SAFE_RATE_VIOLATION_STRING; return SAFE_RATE_VIOLATION_STRING;
case (11201): case (11201):
return SAFE_RATE_RECOVERY_STRING; return SAFE_RATE_RECOVERY_STRING;
case (11202):
return MULTIPLE_RW_INVALID_STRING;
case (11300): case (11300):
return SWITCH_CMD_SENT_STRING; return SWITCH_CMD_SENT_STRING;
case (11301): case (11301):
@ -508,9 +511,9 @@ const char *translateEvents(Event event) {
case (11802): case (11802):
return RESET_OCCURED_STRING; return RESET_OCCURED_STRING;
case (11901): case (11901):
return BOOTING_FIRMWARE_FAILED_STRING; return BOOTING_FIRMWARE_FAILED_EVENT_STRING;
case (11902): case (11902):
return BOOTING_BOOTLOADER_FAILED_STRING; return BOOTING_BOOTLOADER_FAILED_EVENT_STRING;
case (12001): case (12001):
return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING; return SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING;
case (12002): case (12002):

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 13:15:51
*/ */
#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

@ -632,83 +632,6 @@ ReturnValue_t pst::pstTcsAndAcs(FixedTimeslotTaskIF *thisSequence, AcsPstCfg cfg
DeviceHandlerIF::GET_READ); DeviceHandlerIF::GET_READ);
} }
if (cfg.scheduleRws) {
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::SEND_WRITE);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::SEND_WRITE);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::SEND_WRITE);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::SEND_WRITE);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::GET_WRITE);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::GET_WRITE);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::GET_WRITE);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::GET_WRITE);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::SEND_READ);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::SEND_READ);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::SEND_READ);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::SEND_READ);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::GET_READ);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::GET_READ);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::GET_READ);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::GET_READ);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::SEND_WRITE);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::SEND_WRITE);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::SEND_WRITE);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::SEND_WRITE);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::GET_WRITE);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::GET_WRITE);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::GET_WRITE);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::GET_WRITE);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::SEND_READ);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::SEND_READ);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::SEND_READ);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::SEND_READ);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::GET_READ);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::GET_READ);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::GET_READ);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::GET_READ);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::SEND_WRITE);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::SEND_WRITE);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::SEND_WRITE);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::SEND_WRITE);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::GET_WRITE);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::GET_WRITE);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::GET_WRITE);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::GET_WRITE);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::SEND_READ);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::SEND_READ);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::SEND_READ);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::SEND_READ);
//
// thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::GET_READ);
// thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::GET_READ);
// thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::GET_READ);
// thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::GET_READ);
}
if (cfg.scheduleRws) { if (cfg.scheduleRws) {
// this is the torquing cycle // this is the torquing cycle
thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_4_PERIOD, thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_4_PERIOD,
@ -738,67 +661,22 @@ ReturnValue_t pst::pstTcsAndAcs(FixedTimeslotTaskIF *thisSequence, AcsPstCfg cfg
thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_4_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_4_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_4_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_4_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_4_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_4_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_4_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_4_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_4_PERIOD, thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_5_PERIOD,
DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW1, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RW2, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RW3, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RW4, length * config::acs::SCHED_BLOCK_4_PERIOD,
DeviceHandlerIF::GET_READ); DeviceHandlerIF::GET_READ);
} }

View File

@ -331,12 +331,12 @@ bool PdecHandler::checkFrameAna(uint32_t pdecFar) {
FrameAna_t frameAna = static_cast<FrameAna_t>((pdecFar & FRAME_ANA_MASK) >> FRAME_ANA_POSITION); FrameAna_t frameAna = static_cast<FrameAna_t>((pdecFar & FRAME_ANA_MASK) >> FRAME_ANA_POSITION);
switch (frameAna) { switch (frameAna) {
case (FrameAna_t::ABANDONED_CLTU): { case (FrameAna_t::ABANDONED_CLTU): {
triggerEvent(INVALID_TC_FRAME, ABANDONED_CLTU); triggerEvent(INVALID_TC_FRAME, ABANDONED_CLTU_RETVAL);
sif::warning << "PdecHandler::checkFrameAna: Abondoned CLTU" << std::endl; sif::warning << "PdecHandler::checkFrameAna: Abondoned CLTU" << std::endl;
break; break;
} }
case (FrameAna_t::FRAME_DIRTY): { case (FrameAna_t::FRAME_DIRTY): {
triggerEvent(INVALID_TC_FRAME, FRAME_DIRTY); triggerEvent(INVALID_TC_FRAME, FRAME_DIRTY_RETVAL);
sif::warning << "PdecHandler::checkFrameAna: Frame dirty" << std::endl; sif::warning << "PdecHandler::checkFrameAna: Frame dirty" << std::endl;
break; break;
} }
@ -351,13 +351,13 @@ bool PdecHandler::checkFrameAna(uint32_t pdecFar) {
break; break;
} }
case (FrameAna_t::AD_DISCARDED_LOCKOUT): { case (FrameAna_t::AD_DISCARDED_LOCKOUT): {
triggerEvent(INVALID_TC_FRAME, AD_DISCARDED_LOCKOUT); triggerEvent(INVALID_TC_FRAME, AD_DISCARDED_LOCKOUT_RETVAL);
sif::warning << "PdecHandler::checkFrameAna: AD frame discarded because of lockout" sif::warning << "PdecHandler::checkFrameAna: AD frame discarded because of lockout"
<< std::endl; << std::endl;
break; break;
} }
case (FrameAna_t::AD_DISCARDED_WAIT): { case (FrameAna_t::AD_DISCARDED_WAIT): {
triggerEvent(INVALID_TC_FRAME, AD_DISCARDED_LOCKOUT); triggerEvent(INVALID_TC_FRAME, AD_DISCARDED_LOCKOUT_RETVAL);
sif::warning << "PdecHandler::checkFrameAna: AD frame discarded because of wait" << std::endl; sif::warning << "PdecHandler::checkFrameAna: AD frame discarded because of wait" << std::endl;
break; break;
} }
@ -386,40 +386,40 @@ void PdecHandler::handleIReason(uint32_t pdecFar, ReturnValue_t parameter1) {
IReason_t ireason = static_cast<IReason_t>((pdecFar & IREASON_MASK) >> IREASON_POSITION); IReason_t ireason = static_cast<IReason_t>((pdecFar & IREASON_MASK) >> IREASON_POSITION);
switch (ireason) { switch (ireason) {
case (IReason_t::NO_REPORT): { case (IReason_t::NO_REPORT): {
triggerEvent(INVALID_TC_FRAME, parameter1, NO_REPORT); triggerEvent(INVALID_TC_FRAME, parameter1, NO_REPORT_RETVAL);
sif::info << "PdecHandler::handleIReason: No illegal report" << std::endl; sif::info << "PdecHandler::handleIReason: No illegal report" << std::endl;
break; break;
} }
case (IReason_t::ERROR_VERSION_NUMBER): { case (IReason_t::ERROR_VERSION_NUMBER): {
triggerEvent(INVALID_TC_FRAME, parameter1, ERROR_VERSION_NUMBER); triggerEvent(INVALID_TC_FRAME, parameter1, ERROR_VERSION_NUMBER_RETVAL);
sif::info << "PdecHandler::handleIReason: Error in version number and reserved A and B " sif::info << "PdecHandler::handleIReason: Error in version number and reserved A and B "
<< "fields" << std::endl; << "fields" << std::endl;
break; break;
} }
case (IReason_t::ILLEGAL_COMBINATION): { case (IReason_t::ILLEGAL_COMBINATION): {
triggerEvent(INVALID_TC_FRAME, parameter1, ILLEGAL_COMBINATION); triggerEvent(INVALID_TC_FRAME, parameter1, ILLEGAL_COMBINATION_RETVAL);
sif::info << "PdecHandler::handleIReason: Illegal combination (AC) of bypass and control " sif::info << "PdecHandler::handleIReason: Illegal combination (AC) of bypass and control "
<< "command flags" << std::endl; << "command flags" << std::endl;
break; break;
} }
case (IReason_t::INVALID_SC_ID): { case (IReason_t::INVALID_SC_ID): {
triggerEvent(INVALID_TC_FRAME, parameter1, INVALID_SC_ID); triggerEvent(INVALID_TC_FRAME, parameter1, INVALID_SC_ID_RETVAL);
sif::info << "PdecHandler::handleIReason: Invalid spacecraft identifier " << std::endl; sif::info << "PdecHandler::handleIReason: Invalid spacecraft identifier " << std::endl;
break; break;
} }
case (IReason_t::INVALID_VC_ID_MSB): { case (IReason_t::INVALID_VC_ID_MSB): {
triggerEvent(INVALID_TC_FRAME, parameter1, INVALID_VC_ID_MSB); triggerEvent(INVALID_TC_FRAME, parameter1, INVALID_VC_ID_MSB_RETVAL);
sif::info << "PdecHandler::handleIReason: VC identifier bit 0 to 4 did not match " sif::info << "PdecHandler::handleIReason: VC identifier bit 0 to 4 did not match "
<< std::endl; << std::endl;
break; break;
} }
case (IReason_t::INVALID_VC_ID_LSB): { case (IReason_t::INVALID_VC_ID_LSB): {
triggerEvent(INVALID_TC_FRAME, parameter1, INVALID_VC_ID_LSB); triggerEvent(INVALID_TC_FRAME, parameter1, INVALID_VC_ID_LSB_RETVAL);
sif::info << "PdecHandler::handleIReason: VC identifier bit 5 did not match " << std::endl; sif::info << "PdecHandler::handleIReason: VC identifier bit 5 did not match " << std::endl;
break; break;
} }
case (IReason_t::NS_NOT_ZERO): { case (IReason_t::NS_NOT_ZERO): {
triggerEvent(INVALID_TC_FRAME, parameter1, NS_NOT_ZERO); triggerEvent(INVALID_TC_FRAME, parameter1, NS_NOT_ZERO_RETVAL);
sif::info << "PdecHandler::handleIReason: N(S) of BC or BD frame not set to all zeros" sif::info << "PdecHandler::handleIReason: N(S) of BC or BD frame not set to all zeros"
<< std::endl; << std::endl;
break; break;

View File

@ -97,30 +97,30 @@ class PdecHandler : public SystemObject, public ExecutableObjectIF, public HasAc
static constexpr Modes OP_MODE = Modes::IRQ; static constexpr Modes OP_MODE = Modes::IRQ;
static const ReturnValue_t ABANDONED_CLTU = MAKE_RETURN_CODE(0xA0); static const ReturnValue_t ABANDONED_CLTU_RETVAL = MAKE_RETURN_CODE(0xA0);
static const ReturnValue_t FRAME_DIRTY = MAKE_RETURN_CODE(0xA1); static const ReturnValue_t FRAME_DIRTY_RETVAL = MAKE_RETURN_CODE(0xA1);
static const ReturnValue_t FRAME_ILLEGAL_ONE_REASON = MAKE_RETURN_CODE(0xA2); static const ReturnValue_t FRAME_ILLEGAL_ONE_REASON = MAKE_RETURN_CODE(0xA2);
static const ReturnValue_t FRAME_ILLEGAL_MULTIPLE_REASONS = MAKE_RETURN_CODE(0xA2); static const ReturnValue_t FRAME_ILLEGAL_MULTIPLE_REASONS = MAKE_RETURN_CODE(0xA2);
static const ReturnValue_t AD_DISCARDED_LOCKOUT = MAKE_RETURN_CODE(0xA3); static const ReturnValue_t AD_DISCARDED_LOCKOUT_RETVAL = MAKE_RETURN_CODE(0xA3);
static const ReturnValue_t AD_DISCARDED_WAIT = MAKE_RETURN_CODE(0xA4); static const ReturnValue_t AD_DISCARDED_WAIT_RETVAL = MAKE_RETURN_CODE(0xA4);
static const ReturnValue_t AD_DISCARDED_NS_VS = MAKE_RETURN_CODE(0xA5); static const ReturnValue_t AD_DISCARDED_NS_VS = MAKE_RETURN_CODE(0xA5);
//! [EXPORT] : [COMMENT] Received action message with unknown action id //! [EXPORT] : [COMMENT] Received action message with unknown action id
static const ReturnValue_t COMMAND_NOT_IMPLEMENTED = MAKE_RETURN_CODE(0xB0); static const ReturnValue_t COMMAND_NOT_IMPLEMENTED = MAKE_RETURN_CODE(0xB0);
static const ReturnValue_t NO_REPORT = MAKE_RETURN_CODE(0xA6); static const ReturnValue_t NO_REPORT_RETVAL = MAKE_RETURN_CODE(0xA6);
//! Error in version number and reserved A and B fields //! Error in version number and reserved A and B fields
static const ReturnValue_t ERROR_VERSION_NUMBER = MAKE_RETURN_CODE(0xA7); static const ReturnValue_t ERROR_VERSION_NUMBER_RETVAL = MAKE_RETURN_CODE(0xA7);
//! Illegal combination of bypass and control command flag //! Illegal combination of bypass and control command flag
static const ReturnValue_t ILLEGAL_COMBINATION = MAKE_RETURN_CODE(0xA8); static const ReturnValue_t ILLEGAL_COMBINATION_RETVAL = MAKE_RETURN_CODE(0xA8);
//! Spacecraft identifier did not match //! Spacecraft identifier did not match
static const ReturnValue_t INVALID_SC_ID = MAKE_RETURN_CODE(0xA9); static const ReturnValue_t INVALID_SC_ID_RETVAL = MAKE_RETURN_CODE(0xA9);
//! VC identifier bits 0 to 4 did not match //! VC identifier bits 0 to 4 did not match
static const ReturnValue_t INVALID_VC_ID_MSB = MAKE_RETURN_CODE(0xAA); static const ReturnValue_t INVALID_VC_ID_MSB_RETVAL = MAKE_RETURN_CODE(0xAA);
//! VC identifier bit 5 did not match //! VC identifier bit 5 did not match
static const ReturnValue_t INVALID_VC_ID_LSB = MAKE_RETURN_CODE(0xAB); static const ReturnValue_t INVALID_VC_ID_LSB_RETVAL = MAKE_RETURN_CODE(0xAB);
//! N(S) of BC or BD frame not set to all zeros //! N(S) of BC or BD frame not set to all zeros
static const ReturnValue_t NS_NOT_ZERO = MAKE_RETURN_CODE(0xAC); static const ReturnValue_t NS_NOT_ZERO_RETVAL = MAKE_RETURN_CODE(0xAC);
//! Invalid BC control command //! Invalid BC control command
static const ReturnValue_t INVALID_BC_CC = MAKE_RETURN_CODE(0xAE); static const ReturnValue_t INVALID_BC_CC = MAKE_RETURN_CODE(0xAE);

View File

@ -57,7 +57,7 @@
</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=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -119,7 +119,7 @@
</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=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -187,7 +187,7 @@
</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=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -255,7 +255,7 @@
</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=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -418,7 +418,7 @@
</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=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -580,7 +580,7 @@
</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=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -680,7 +680,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 +750,7 @@
</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-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=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -917,7 +917,7 @@
</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=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -1084,7 +1084,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 +1149,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 +1317,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|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=""/>
</sourceEntries> </sourceEntries>
</configuration> </configuration>
</storageModule> </storageModule>
@ -1386,7 +1386,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>
@ -1487,9 +1487,6 @@
<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.1707795689.1939781894;cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.1707795689.1939781894.;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.2002501811;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.input.1316209993"> <scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.1707795689.1939781894;cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.1707795689.1939781894.;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.2002501811;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.input.1316209993">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/> <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo> </scannerConfigBuildInfo>
<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.1707795689;cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.1707795689.;ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.1898420988;ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.input.2134154524">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo>
<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443;cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.;cdt.managedbuild.tool.gnu.cpp.compiler.mingw.base.646655988;cdt.managedbuild.tool.gnu.cpp.compiler.input.1437856797"> <scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443;cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.;cdt.managedbuild.tool.gnu.cpp.compiler.mingw.base.646655988;cdt.managedbuild.tool.gnu.cpp.compiler.input.1437856797">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/> <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo> </scannerConfigBuildInfo>
@ -1532,9 +1529,6 @@
<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.1707795689.1171630561;cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.1707795689.1171630561.;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.1477130926;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.input.779990384"> <scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.1707795689.1171630561;cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.1707795689.1171630561.;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.1477130926;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.input.779990384">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/> <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo> </scannerConfigBuildInfo>
<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.1707795689;cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.1707795689.;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.978379831;ilg.gnuarmeclipse.managedbuild.cross.tool.c.compiler.input.780507143">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo>
<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851;cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.;ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.1595165802;ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.input.1925043110"> <scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851;cdt.managedbuild.toolchain.gnu.mingw.base.1455833186.1840876443.2117915473.688890851.;ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.1595165802;ilg.gnuarmeclipse.managedbuild.cross.tool.cpp.compiler.input.1925043110">
<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/> <autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
</scannerConfigBuildInfo> </scannerConfigBuildInfo>

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),
@ -263,7 +264,16 @@ 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}; double mgtDpDes[3] = {0, 0, 0};
@ -385,10 +395,7 @@ 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);
} }
int32_t cmdSpeedRws[4] = {0, 0, 0, 0}; int32_t cmdSpeedRws[4] = {0, 0, 0, 0};

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"
@ -17,7 +18,6 @@
#include "eive/objects.h" #include "eive/objects.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 "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"
#include "mission/trace.h" #include "mission/trace.h"
@ -50,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;
@ -84,10 +85,10 @@ class AcsController : public ExtendedControllerBase, public ReceivesParameterMes
/* ACS Actuation Datasets */ /* ACS Actuation Datasets */
IMTQ::DipoleActuationSet dipoleSet = IMTQ::DipoleActuationSet(objects::IMTQ_HANDLER); IMTQ::DipoleActuationSet dipoleSet = IMTQ::DipoleActuationSet(objects::IMTQ_HANDLER);
RwDefinitions::RwSpeedActuationSet rw1SpeedSet = RwDefinitions::RwSpeedActuationSet(objects::RW1); rws::RwSpeedActuationSet rw1SpeedSet = rws::RwSpeedActuationSet(objects::RW1);
RwDefinitions::RwSpeedActuationSet rw2SpeedSet = RwDefinitions::RwSpeedActuationSet(objects::RW2); rws::RwSpeedActuationSet rw2SpeedSet = rws::RwSpeedActuationSet(objects::RW2);
RwDefinitions::RwSpeedActuationSet rw3SpeedSet = RwDefinitions::RwSpeedActuationSet(objects::RW3); rws::RwSpeedActuationSet rw3SpeedSet = rws::RwSpeedActuationSet(objects::RW3);
RwDefinitions::RwSpeedActuationSet rw4SpeedSet = RwDefinitions::RwSpeedActuationSet(objects::RW4); rws::RwSpeedActuationSet rw4SpeedSet = rws::RwSpeedActuationSet(objects::RW4);
/* ACS Datasets */ /* ACS Datasets */
// MGMs // MGMs
acsctrl::MgmDataRaw mgmDataRaw; acsctrl::MgmDataRaw mgmDataRaw;

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

@ -294,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;

View File

@ -789,8 +789,8 @@ class AcsParameters : public HasParametersIF {
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; uint16_t rampTime = 10;
@ -802,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;

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

@ -567,7 +567,7 @@ void SensorProcessing::processGps(const double gpsLatitude, const double gpsLong
gcLatitude = atan(factor * tan(latitudeRad)); gcLatitude = atan(factor * tan(latitudeRad));
// Calculation of the satellite velocity in earth fixed frame // Calculation of the satellite velocity in earth fixed frame
double posSatE[3] = {0, 0, 0}, deltaDistance[3] = {0, 0, 0}, gpsVelocityE[3] = {0, 0, 0}; double deltaDistance[3] = {0, 0, 0};
MathOperations<double>::cartesianFromLatLongAlt(latitudeRad, gdLongitude, gpsAltitude, posSatE); MathOperations<double>::cartesianFromLatLongAlt(latitudeRad, gdLongitude, gpsAltitude, posSatE);
if (validSavedPosSatE && if (validSavedPosSatE &&
(gpsUnixSeconds - timeOfSavedPosSatE) < (gpsParameters->timeDiffVelocityMax)) { (gpsUnixSeconds - timeOfSavedPosSatE) < (gpsParameters->timeDiffVelocityMax)) {

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

@ -434,7 +434,7 @@ ReturnValue_t GyroADIS1650XHandler::spiSendCallback(SpiComIF *comIf, SpiCookie *
// Prepare transfer // Prepare transfer
int fileDescriptor = 0; int fileDescriptor = 0;
std::string device = comIf->getSpiDev(); std::string device = comIf->getSpiDev();
UnixFileGuard fileHelper(device, &fileDescriptor, O_RDWR, "SpiComIF::sendMessage"); UnixFileGuard fileHelper(device, fileDescriptor, O_RDWR, "SpiComIF::sendMessage");
if (fileHelper.getOpenResult() != returnvalue::OK) { if (fileHelper.getOpenResult() != returnvalue::OK) {
return SpiComIF::OPENING_FILE_FAILED; return SpiComIF::OPENING_FILE_FAILED;
} }

View File

@ -289,7 +289,7 @@ void HeaterHandler::handleSwitchOffCommand(heater::Switchers heaterIdx) {
<< " low" << std::endl; << " low" << std::endl;
triggerEvent(GPIO_PULL_LOW_FAILED, result); triggerEvent(GPIO_PULL_LOW_FAILED, result);
} else { } else {
auto result = heaterMutex->lockMutex(); result = heaterMutex->lockMutex();
heater.switchState = OFF; heater.switchState = OFF;
if (result == returnvalue::OK) { if (result == returnvalue::OK) {
heaterMutex->unlockMutex(); heaterMutex->unlockMutex();

View File

@ -722,7 +722,7 @@ ReturnValue_t PayloadPcduHandler::transferAsTwo(SpiComIF* comIf, SpiCookie* cook
int retval = 0; int retval = 0;
// Prepare transfer // Prepare transfer
int fileDescriptor = 0; int fileDescriptor = 0;
UnixFileGuard fileHelper(comIf->getSpiDev(), &fileDescriptor, O_RDWR, "SpiComIF::sendMessage"); UnixFileGuard fileHelper(comIf->getSpiDev(), fileDescriptor, O_RDWR, "SpiComIF::sendMessage");
if (fileHelper.getOpenResult() != returnvalue::OK) { if (fileHelper.getOpenResult() != returnvalue::OK) {
return SpiComIF::OPENING_FILE_FAILED; return SpiComIF::OPENING_FILE_FAILED;
} }

View File

@ -2,6 +2,7 @@
#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"
@ -27,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);
} }
@ -39,32 +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::SET_SPEED: case InternalState::DEFAULT: {
*id = RwDefinitions::SET_SPEED; *id = rws::REQUEST_ID;
internalState = InternalState::GET_RESET_STATUS;
break;
case InternalState::GET_RESET_STATUS:
*id = RwDefinitions::GET_LAST_RESET_STATUS;
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::CLEAR_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;
@ -82,27 +70,8 @@ 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;
}
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 (commandData != nullptr && commandDataLen != 6) { if (commandData != nullptr && 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;
@ -133,15 +102,33 @@ ReturnValue_t RwHandler::buildCommandFromCommand(DeviceCommandId_t deviceCommand
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
return result; return result;
} }
result = prepareSetSpeedCmd(); // 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:
@ -151,162 +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;
*foundId = RwDefinitions::GET_LAST_RESET_STATUS;
break;
} }
case (RwDefinitions::CLEAR_LAST_RESET_STATUS): { if (remainingSize > 0) {
*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; *foundLen = remainingSize;
return returnvalue::FAILED; *foundId = rws::REPLY_ID;
} }
}
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 currentId, 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(currentId);
/** Received in little endian byte order */ // arrayprinter::print(packetPtr, packetLen);
uint16_t replyCrc = *(packet + sizeOfReply - 1) << 8 | *(packet + sizeOfReply - 2); uint16_t replyCrc = 0;
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);
if (CRC::crc16ccitt(packetPtr, packetLen - 2) != replyCrc) {
sif::error << "RwHandler::interpretDeviceReply: CRC error for ID " << id << std::endl;
return CRC_ERROR; return CRC_ERROR;
} }
if (packetPtr[1] == rws::STATE_ERROR) {
switch (id) { sif::error << "RwHandler::interpretDeviceReply: Command execution failed. Command id: " << id
case (RwDefinitions::GET_LAST_RESET_STATUS): { << std::endl;
handleResetStatusReply(packet); result = EXECUTION_FAILED;
break;
} }
case (RwDefinitions::GET_RW_STATUS): {
handleGetRwStatusReply(packet);
break;
}
case (RwDefinitions::CLEAR_LAST_RESET_STATUS):
case (RwDefinitions::INIT_RW_CONTROLLER):
case (RwDefinitions::SET_SPEED):
// no reply data expected
break;
case (RwDefinitions::GET_TEMPERATURE): {
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; return returnvalue::OK;
};
if (replies.wasSetSpeedReplyRead()) {
status = checkPacket(rws::DeviceCommandId::SET_SPEED, replies.getSetSpeedReply());
if (status != returnvalue::OK) {
result = status;
}
}
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::RW_SPEED, &rwSpeed); localDataPoolMap.emplace(rws::RW_SPEED, &rwSpeed);
localDataPoolMap.emplace(RwDefinitions::RAMP_TIME, &rampTime); localDataPoolMap.emplace(rws::RAMP_TIME, &rampTime);
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}));
poolManager.subscribeForDiagPeriodicPacket( poolManager.subscribeForDiagPeriodicPacket(
subdp::DiagnosticsHkPeriodicParams(statusSet.getSid(), false, 5.0)); subdp::DiagnosticsHkPeriodicParams(statusSet.getSid(), false, 5.0));
poolManager.subscribeForRegularPeriodicPacket( poolManager.subscribeForRegularPeriodicPacket(
@ -316,15 +302,6 @@ ReturnValue_t RwHandler::initializeLocalDataPool(localpool::DataPool& localDataP
return returnvalue::OK; return returnvalue::OK;
} }
void RwHandler::prepareSimpleCommand(DeviceCommandId_t id) {
commandBuffer[0] = static_cast<uint8_t>(id);
uint16_t crc = CRC::crc16ccitt(commandBuffer, 1, 0xFFFF);
commandBuffer[1] = static_cast<uint8_t>(crc & 0xFF);
commandBuffer[2] = static_cast<uint8_t>(crc >> 8 & 0xFF);
rawPacket = commandBuffer;
rawPacketLen = 3;
}
ReturnValue_t RwHandler::checkSpeedAndRampTime() { ReturnValue_t RwHandler::checkSpeedAndRampTime() {
int32_t speed = 0; int32_t speed = 0;
uint16_t rampTime = 0; uint16_t rampTime = 0;
@ -342,34 +319,14 @@ ReturnValue_t RwHandler::checkSpeedAndRampTime() {
return returnvalue::OK; return returnvalue::OK;
} }
ReturnValue_t RwHandler::prepareSetSpeedCmd() {
commandBuffer[0] = static_cast<uint8_t>(RwDefinitions::SET_SPEED);
uint8_t* serPtr = commandBuffer + 1;
size_t serSize = 1;
rwSpeedActuationSet.setValidityBufferGeneration(false);
ReturnValue_t result = rwSpeedActuationSet.serialize(&serPtr, &serSize, sizeof(commandBuffer),
SerializeIF::Endianness::LITTLE);
rwSpeedActuationSet.setValidityBufferGeneration(true);
if (result != returnvalue::OK) {
return result;
}
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;
return result;
}
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) {
@ -408,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;
} }
@ -442,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,7 +3,7 @@
#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"
@ -42,24 +42,6 @@ class RwHandler : public DeviceHandlerBase {
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;
@ -74,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
@ -87,40 +70,43 @@ 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;
RwDefinitions::RwSpeedActuationSet rwSpeedActuationSet; rws::RwSpeedActuationSet rwSpeedActuationSet;
uint8_t commandBuffer[RwDefinitions::MAX_CMD_SIZE]; uint8_t commandBuffer[32];
uint8_t rwIdx; uint8_t rwIdx;
PoolEntry<int32_t> rwSpeed = PoolEntry<int32_t>({0}); PoolEntry<int32_t> rwSpeed = PoolEntry<int32_t>({0});
PoolEntry<uint16_t> rampTime = PoolEntry<uint16_t>({10}); PoolEntry<uint16_t> rampTime = PoolEntry<uint16_t>({10});
enum class InternalState { enum class InternalState {
GET_RESET_STATUS, DEFAULT,
CLEAR_RESET_STATUS, GET_TM,
READ_TEMPERATURE, INIT_RW_CONTROLLER,
SET_SPEED, RESET_MCU,
GET_RW_SATUS // GET_RESET_STATUS,
// CLEAR_RESET_STATUS,
// READ_TEMPERATURE,
// SET_SPEED,
// GET_RW_SATUS
}; };
InternalState internalState = InternalState::GET_RESET_STATUS; InternalState internalState = InternalState::DEFAULT;
size_t sizeOfReply = 0;
/** /**
* @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
@ -134,7 +120,7 @@ class RwHandler : public DeviceHandlerBase {
* an action message or set in the software. * an action message or set in the software.
* @return returnvalue::OK if successful, otherwise error code. * @return returnvalue::OK if successful, otherwise error code.
*/ */
ReturnValue_t prepareSetSpeedCmd(); // 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

@ -279,7 +279,7 @@ ReturnValue_t SyrlinksHandler::scanForReply(const uint8_t* start, size_t remaini
break; break;
default: default:
sif::warning << "SyrlinksHkHandler::scanForReply: Unknown reply identifier" << std::endl; sif::warning << "SyrlinksHkHandler::scanForReply: Unknown reply identifier" << std::endl;
result = IGNORE_REPLY_DATA; result = IGNORE_FULL_PACKET;
break; break;
} }

View File

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

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,
@ -68,32 +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;
enum SetIds : uint32_t { GET_LAST_RESET_STATUS = 2,
TEMPERATURE_SET_ID = GET_TEMPERATURE, CLEAR_LAST_RESET_STATUS = 3,
STATUS_SET_ID = GET_RW_STATUS, GET_RW_STATUS = 4,
LAST_RESET_ID = GET_LAST_RESET_STATUS, INIT_RW_CONTROLLER = 5,
TM_SET_ID = GET_TM, SET_SPEED = 6,
SPEED_CMD_SET = 10, 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;
@ -112,11 +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) StatusSet(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, rws::SetIds::STATUS_SET_ID) {}
: StaticLocalDataSet(owner, RwDefinitions::SetIds::STATUS_SET_ID) {}
StatusSet(object_id_t objectId) StatusSet(object_id_t objectId)
: StaticLocalDataSet(sid_t(objectId, RwDefinitions::SetIds::STATUS_SET_ID)) {} : 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);
@ -133,10 +175,10 @@ 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) LastResetSatus(HasLocalDataPoolIF* owner)
: StaticLocalDataSet(owner, RwDefinitions::SetIds::LAST_RESET_ID) {} : StaticLocalDataSet(owner, rws::SetIds::LAST_RESET_ID) {}
LastResetSatus(object_id_t objectId) LastResetSatus(object_id_t objectId)
: StaticLocalDataSet(sid_t(objectId, RwDefinitions::SetIds::LAST_RESET_ID)) {} : 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 =
@ -153,11 +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) TmDataset(HasLocalDataPoolIF* owner) : StaticLocalDataSet(owner, rws::SetIds::TM_SET_ID) {}
: StaticLocalDataSet(owner, RwDefinitions::SetIds::TM_SET_ID) {}
TmDataset(object_id_t objectId) TmDataset(object_id_t objectId) : StaticLocalDataSet(sid_t(objectId, rws::SetIds::TM_SET_ID)) {}
: StaticLocalDataSet(sid_t(objectId, RwDefinitions::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);
@ -209,9 +249,9 @@ class RwSpeedActuationSet : public StaticLocalDataSet<2> {
public: public:
RwSpeedActuationSet(HasLocalDataPoolIF& owner) RwSpeedActuationSet(HasLocalDataPoolIF& owner)
: StaticLocalDataSet(&owner, RwDefinitions::SetIds::SPEED_CMD_SET) {} : StaticLocalDataSet(&owner, rws::SetIds::SPEED_CMD_SET) {}
RwSpeedActuationSet(object_id_t objectId) RwSpeedActuationSet(object_id_t objectId)
: StaticLocalDataSet(sid_t(objectId, RwDefinitions::SetIds::SPEED_CMD_SET)) {} : StaticLocalDataSet(sid_t(objectId, rws::SetIds::SPEED_CMD_SET)) {}
void setRwSpeed(int32_t rwSpeed_, uint16_t rampTime_) { void setRwSpeed(int32_t rwSpeed_, uint16_t rampTime_) {
if (rwSpeed.value != rwSpeed_) { if (rwSpeed.value != rwSpeed_) {
@ -228,12 +268,71 @@ class RwSpeedActuationSet : public StaticLocalDataSet<2> {
} }
private: private:
lp_var_t<int32_t> rwSpeed = lp_var_t<int32_t> rwSpeed = lp_var_t<int32_t>(sid.objectId, rws::PoolIds::RW_SPEED, this);
lp_var_t<int32_t>(sid.objectId, RwDefinitions::PoolIds::RW_SPEED, this); lp_var_t<uint16_t> rampTime = lp_var_t<uint16_t>(sid.objectId, rws::PoolIds::RAMP_TIME, this);
lp_var_t<uint16_t> rampTime =
lp_var_t<uint16_t>(sid.objectId, RwDefinitions::PoolIds::RAMP_TIME, this);
}; };
} // namespace RwDefinitions } // namespace rws
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_RWDEFINITIONS_H_ */ /**
* 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();
} }
@ -54,22 +59,24 @@ void AcsSubsystem::handleEventMessages() {
EventMessage event; EventMessage event;
for (ReturnValue_t result = eventQueue->receiveMessage(&event); result == returnvalue::OK; for (ReturnValue_t result = eventQueue->receiveMessage(&event); result == returnvalue::OK;
result = eventQueue->receiveMessage(&event)) { result = eventQueue->receiveMessage(&event)) {
ReturnValue_t status;
switch (event.getMessageId()) { switch (event.getMessageId()) {
case EventMessage::EVENT_MESSAGE: case EventMessage::EVENT_MESSAGE:
if (event.getEvent() == acs::SAFE_RATE_VIOLATION) { if (event.getEvent() == acs::SAFE_RATE_VIOLATION) {
CommandMessage msg; CommandMessage msg;
ModeMessage::setCmdModeMessage(msg, acs::AcsMode::DETUMBLE, 0); ModeMessage::setCmdModeMessage(msg, acs::AcsMode::DETUMBLE, 0);
ReturnValue_t result = commandQueue->sendMessage(commandQueue->getId(), &msg); status = commandQueue->sendMessage(commandQueue->getId(), &msg);
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
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); status = commandQueue->sendMessage(commandQueue->getId(), &msg);
if (result != returnvalue::OK) { if (status != 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) {

View File

@ -4,5 +4,6 @@ add_subdirectory(mocks)
target_sources(${UNITTEST_NAME} PRIVATE target_sources(${UNITTEST_NAME} PRIVATE
main.cpp main.cpp
testEnvironment.cpp testEnvironment.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);
}
}