Merge remote-tracking branch 'origin/develop' into irini
Some checks failed
EIVE/eive-obsw/pipeline/head There was a failure building this commit

This commit is contained in:
2022-05-26 12:08:07 +02:00
271 changed files with 11845 additions and 6684 deletions

View File

@ -6,6 +6,4 @@ add_subdirectory(devices)
add_subdirectory(fsfwconfig)
add_subdirectory(obc)
target_sources(${OBSW_NAME} PUBLIC
ObjectFactory.cpp
)
target_sources(${OBSW_NAME} PUBLIC ObjectFactory.cpp)

View File

@ -7,12 +7,14 @@
#include <fsfw_hal/linux/spi/SpiComIF.h>
#include <fsfw_hal/linux/spi/SpiCookie.h>
#include <linux/callbacks/gpioCallbacks.h>
#include <linux/devices/Max31865RtdLowlevelHandler.h>
#include <mission/devices/Max31865EiveHandler.h>
#include <mission/devices/Max31865PT1000Handler.h>
#include <mission/devices/SusHandler.h>
#include <mission/system/RtdFdir.h>
#include <mission/system/SusAssembly.h>
#include <mission/system/SusFdir.h>
#include <mission/system/TcsBoardAssembly.h>
#include <mission/system/fdir/RtdFdir.h>
#include <mission/system/fdir/SusFdir.h>
#include "OBSWConfig.h"
#include "devConf.h"
@ -62,93 +64,104 @@ void ObjectFactory::createSunSensorComponents(GpioIF* gpioComIF, SpiComIF* spiCo
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
gpioCookieSus->addGpio(gpioIds::CS_SUS_11, susgpio);
gpioComIF->addGpios(gpioCookieSus);
gpioChecker(gpioComIF->addGpios(gpioCookieSus), "Sun Sensors");
#if OBSW_ADD_SUN_SENSORS == 1
SusFdir* fdir = nullptr;
std::array<SusHandler*, 12> susHandlers = {};
SpiCookie* spiCookie =
new SpiCookie(addresses::SUS_0, gpioIds::CS_SUS_0, spiDev, SUS::MAX_CMD_SIZE,
spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ);
susHandlers[0] = new SusHandler(objects::SUS_0, 0, objects::SPI_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_0);
SpiCookie* spiCookie = new SpiCookie(addresses::SUS_0, gpioIds::CS_SUS_0, SUS::MAX_CMD_SIZE,
spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ);
susHandlers[0] =
new SusHandler(objects::SUS_0_N_LOC_XFYFZM_PT_XF, 0, objects::SPI_MAIN_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_0_N_LOC_XFYFZM_PT_XF);
susHandlers[0]->setParent(objects::SUS_BOARD_ASS);
susHandlers[0]->setCustomFdir(fdir);
spiCookie = new SpiCookie(addresses::SUS_1, gpioIds::CS_SUS_1, spiDev, SUS::MAX_CMD_SIZE,
spiCookie = new SpiCookie(addresses::SUS_1, gpioIds::CS_SUS_1, SUS::MAX_CMD_SIZE,
spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ);
susHandlers[1] = new SusHandler(objects::SUS_1, 1, objects::SPI_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_1);
susHandlers[1] =
new SusHandler(objects::SUS_1_N_LOC_XBYFZM_PT_XB, 1, objects::SPI_MAIN_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_1_N_LOC_XBYFZM_PT_XB);
susHandlers[1]->setParent(objects::SUS_BOARD_ASS);
susHandlers[1]->setCustomFdir(fdir);
spiCookie = new SpiCookie(addresses::SUS_2, gpioIds::CS_SUS_2, spiDev, SUS::MAX_CMD_SIZE,
spiCookie = new SpiCookie(addresses::SUS_2, gpioIds::CS_SUS_2, SUS::MAX_CMD_SIZE,
spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ);
susHandlers[2] = new SusHandler(objects::SUS_2, 2, objects::SPI_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_2);
susHandlers[2] =
new SusHandler(objects::SUS_2_N_LOC_XFYBZB_PT_YB, 2, objects::SPI_MAIN_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_2_N_LOC_XFYBZB_PT_YB);
susHandlers[2]->setParent(objects::SUS_BOARD_ASS);
susHandlers[2]->setCustomFdir(fdir);
spiCookie = new SpiCookie(addresses::SUS_3, gpioIds::CS_SUS_3, spiDev, SUS::MAX_CMD_SIZE,
spiCookie = new SpiCookie(addresses::SUS_3, gpioIds::CS_SUS_3, SUS::MAX_CMD_SIZE,
spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ);
susHandlers[3] = new SusHandler(objects::SUS_3, 3, objects::SPI_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_3);
susHandlers[3] =
new SusHandler(objects::SUS_3_N_LOC_XFYBZF_PT_YF, 3, objects::SPI_MAIN_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_3_N_LOC_XFYBZF_PT_YF);
susHandlers[3]->setParent(objects::SUS_BOARD_ASS);
susHandlers[3]->setCustomFdir(fdir);
spiCookie = new SpiCookie(addresses::SUS_4, gpioIds::CS_SUS_4, spiDev, SUS::MAX_CMD_SIZE,
spiCookie = new SpiCookie(addresses::SUS_4, gpioIds::CS_SUS_4, SUS::MAX_CMD_SIZE,
spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ);
susHandlers[4] = new SusHandler(objects::SUS_4, 4, objects::SPI_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_4);
susHandlers[4] =
new SusHandler(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, 4, objects::SPI_MAIN_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_4_N_LOC_XMYFZF_PT_ZF);
susHandlers[4]->setParent(objects::SUS_BOARD_ASS);
susHandlers[4]->setCustomFdir(fdir);
spiCookie = new SpiCookie(addresses::SUS_5, gpioIds::CS_SUS_5, spiDev, SUS::MAX_CMD_SIZE,
spiCookie = new SpiCookie(addresses::SUS_5, gpioIds::CS_SUS_5, SUS::MAX_CMD_SIZE,
spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ);
susHandlers[5] = new SusHandler(objects::SUS_5, 5, objects::SPI_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_5);
susHandlers[5] =
new SusHandler(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, 5, objects::SPI_MAIN_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_5_N_LOC_XFYMZB_PT_ZB);
susHandlers[5]->setParent(objects::SUS_BOARD_ASS);
susHandlers[5]->setCustomFdir(fdir);
spiCookie = new SpiCookie(addresses::SUS_6, gpioIds::CS_SUS_6, spiDev, SUS::MAX_CMD_SIZE,
spiCookie = new SpiCookie(addresses::SUS_6, gpioIds::CS_SUS_6, SUS::MAX_CMD_SIZE,
spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ);
susHandlers[6] = new SusHandler(objects::SUS_6, 6, objects::SPI_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_6);
susHandlers[6] =
new SusHandler(objects::SUS_6_R_LOC_XFYBZM_PT_XF, 6, objects::SPI_MAIN_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_6_R_LOC_XFYBZM_PT_XF);
susHandlers[6]->setParent(objects::SUS_BOARD_ASS);
susHandlers[6]->setCustomFdir(fdir);
spiCookie = new SpiCookie(addresses::SUS_7, gpioIds::CS_SUS_7, spiDev, SUS::MAX_CMD_SIZE,
spiCookie = new SpiCookie(addresses::SUS_7, gpioIds::CS_SUS_7, SUS::MAX_CMD_SIZE,
spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ);
susHandlers[7] = new SusHandler(objects::SUS_7, 7, objects::SPI_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_7);
susHandlers[7] =
new SusHandler(objects::SUS_7_R_LOC_XBYBZM_PT_XB, 7, objects::SPI_MAIN_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_7_R_LOC_XBYBZM_PT_XB);
susHandlers[7]->setParent(objects::SUS_BOARD_ASS);
susHandlers[7]->setCustomFdir(fdir);
spiCookie = new SpiCookie(addresses::SUS_8, gpioIds::CS_SUS_8, spiDev, SUS::MAX_CMD_SIZE,
spiCookie = new SpiCookie(addresses::SUS_8, gpioIds::CS_SUS_8, SUS::MAX_CMD_SIZE,
spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ);
susHandlers[8] = new SusHandler(objects::SUS_8, 8, objects::SPI_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_8);
susHandlers[8] =
new SusHandler(objects::SUS_8_R_LOC_XBYBZB_PT_YB, 8, objects::SPI_MAIN_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_8_R_LOC_XBYBZB_PT_YB);
susHandlers[8]->setParent(objects::SUS_BOARD_ASS);
susHandlers[8]->setCustomFdir(fdir);
spiCookie = new SpiCookie(addresses::SUS_9, gpioIds::CS_SUS_9, spiDev, SUS::MAX_CMD_SIZE,
spiCookie = new SpiCookie(addresses::SUS_9, gpioIds::CS_SUS_9, SUS::MAX_CMD_SIZE,
spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ);
susHandlers[9] = new SusHandler(objects::SUS_9, 9, objects::SPI_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_9);
susHandlers[9] =
new SusHandler(objects::SUS_9_R_LOC_XBYBZB_PT_YF, 9, objects::SPI_MAIN_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_9_R_LOC_XBYBZB_PT_YF);
susHandlers[9]->setParent(objects::SUS_BOARD_ASS);
susHandlers[9]->setCustomFdir(fdir);
spiCookie = new SpiCookie(addresses::SUS_10, gpioIds::CS_SUS_10, spiDev, SUS::MAX_CMD_SIZE,
spiCookie = new SpiCookie(addresses::SUS_10, gpioIds::CS_SUS_10, SUS::MAX_CMD_SIZE,
spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ);
susHandlers[10] = new SusHandler(objects::SUS_10, 10, objects::SPI_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_10);
susHandlers[10] =
new SusHandler(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, 10, objects::SPI_MAIN_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_10_N_LOC_XMYBZF_PT_ZF);
susHandlers[10]->setParent(objects::SUS_BOARD_ASS);
susHandlers[10]->setCustomFdir(fdir);
spiCookie = new SpiCookie(addresses::SUS_11, gpioIds::CS_SUS_11, spiDev, SUS::MAX_CMD_SIZE,
spiCookie = new SpiCookie(addresses::SUS_11, gpioIds::CS_SUS_11, SUS::MAX_CMD_SIZE,
spi::SUS_MAX_1227_MODE, spi::SUS_MAX1227_SPI_FREQ);
susHandlers[11] = new SusHandler(objects::SUS_11, 11, objects::SPI_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_11);
susHandlers[11] =
new SusHandler(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, 11, objects::SPI_MAIN_COM_IF, spiCookie);
fdir = new SusFdir(objects::SUS_11_R_LOC_XBYMZB_PT_ZB);
susHandlers[11]->setParent(objects::SUS_BOARD_ASS);
susHandlers[11]->setCustomFdir(fdir);
@ -163,10 +176,13 @@ void ObjectFactory::createSunSensorComponents(GpioIF* gpioComIF, SpiComIF* spiCo
#endif
}
}
std::array<object_id_t, 12> susIds = {objects::SUS_0, objects::SUS_1, objects::SUS_2,
objects::SUS_3, objects::SUS_4, objects::SUS_5,
objects::SUS_6, objects::SUS_7, objects::SUS_8,
objects::SUS_9, objects::SUS_10, objects::SUS_11};
std::array<object_id_t, 12> susIds = {
objects::SUS_0_N_LOC_XFYFZM_PT_XF, objects::SUS_1_N_LOC_XBYFZM_PT_XB,
objects::SUS_2_N_LOC_XFYBZB_PT_YB, objects::SUS_3_N_LOC_XFYBZF_PT_YF,
objects::SUS_4_N_LOC_XMYFZF_PT_ZF, objects::SUS_5_N_LOC_XFYMZB_PT_ZB,
objects::SUS_6_R_LOC_XFYBZM_PT_XF, objects::SUS_7_R_LOC_XBYBZM_PT_XB,
objects::SUS_8_R_LOC_XBYBZB_PT_YB, objects::SUS_9_R_LOC_XBYBZB_PT_YF,
objects::SUS_10_N_LOC_XMYBZF_PT_ZF, objects::SUS_11_R_LOC_XBYMZB_PT_ZB};
SusAssHelper susAssHelper = SusAssHelper(susIds);
auto susAss =
new SusAssembly(objects::SUS_BOARD_ASS, objects::NO_OBJECT, pwrSwitcher, susAssHelper);
@ -175,7 +191,7 @@ void ObjectFactory::createSunSensorComponents(GpioIF* gpioComIF, SpiComIF* spiCo
}
void ObjectFactory::createRtdComponents(std::string spiDev, GpioIF* gpioComIF,
PowerSwitchIF* pwrSwitcher) {
PowerSwitchIF* pwrSwitcher, SpiComIF* comIF) {
using namespace gpio;
GpioCookie* rtdGpioCookie = new GpioCookie;
@ -228,11 +244,11 @@ void ObjectFactory::createRtdComponents(std::string spiDev, GpioIF* gpioComIF,
&gpioCallbacks::spiCsDecoderCallback, gpioComIF);
rtdGpioCookie->addGpio(gpioIds::RTD_IC_18, gpioRtdIc15);
gpioComIF->addGpios(rtdGpioCookie);
gpioChecker(gpioComIF->addGpios(rtdGpioCookie), "RTDs");
#if OBSW_ADD_RTD_DEVICES == 1
static constexpr uint8_t NUMBER_RTDS = 16;
std::array<std::pair<address_t, gpioId_t>, NUMBER_RTDS> cookieArgs = {{
using namespace EiveMax31855;
std::array<std::pair<address_t, gpioId_t>, NUM_RTDS> cookieArgs = {{
{addresses::RTD_IC_3, gpioIds::RTD_IC_3},
{addresses::RTD_IC_4, gpioIds::RTD_IC_4},
{addresses::RTD_IC_5, gpioIds::RTD_IC_5},
@ -250,37 +266,61 @@ void ObjectFactory::createRtdComponents(std::string spiDev, GpioIF* gpioComIF,
{addresses::RTD_IC_17, gpioIds::RTD_IC_17},
{addresses::RTD_IC_18, gpioIds::RTD_IC_18},
}};
std::array<object_id_t, NUMBER_RTDS> rtdIds = {
objects::RTD_IC_3, objects::RTD_IC_4, objects::RTD_IC_5, objects::RTD_IC_6,
objects::RTD_IC_7, objects::RTD_IC_8, objects::RTD_IC_9, objects::RTD_IC_10,
objects::RTD_IC_11, objects::RTD_IC_12, objects::RTD_IC_13, objects::RTD_IC_14,
objects::RTD_IC_15, objects::RTD_IC_16, objects::RTD_IC_17, objects::RTD_IC_18};
std::array<SpiCookie*, NUMBER_RTDS> rtdCookies = {};
std::array<Max31865PT1000Handler*, NUMBER_RTDS> rtds = {};
// HSPD: Heatspreader
std::array<std::pair<object_id_t, std::string>, NUM_RTDS> rtdInfos = {{
{objects::RTD_0_IC3_PLOC_HEATSPREADER, "RTD_0_PLOC_HSPD"},
{objects::RTD_1_IC4_PLOC_MISSIONBOARD, "RTD_1_PLOC_MISSIONBRD"},
{objects::RTD_2_IC5_4K_CAMERA, "RTD_2_4K_CAMERA"},
{objects::RTD_3_IC6_DAC_HEATSPREADER, "RTD_3_DAC_HSPD"},
{objects::RTD_4_IC7_STARTRACKER, "RTD_4_STARTRACKER"},
{objects::RTD_5_IC8_RW1_MX_MY, "RTD_5_RW1_MX_MY"},
{objects::RTD_6_IC9_DRO, "RTD_6_DRO"},
{objects::RTD_7_IC10_SCEX, "RTD_7_SCEX"},
{objects::RTD_8_IC11_X8, "RTD_8_X8"},
{objects::RTD_9_IC12_HPA, "RTD_9_HPA"},
{objects::RTD_10_IC13_PL_TX, "RTD_10_PL_TX,"},
{objects::RTD_11_IC14_MPA, "RTD_11_MPA"},
{objects::RTD_12_IC15_ACU, "RTD_12_ACU"},
{objects::RTD_13_IC16_PLPCDU_HEATSPREADER, "RTD_13_PLPCDU_HSPD"},
{objects::RTD_14_IC17_TCS_BOARD, "RTD_14_TCS_BOARD"},
{objects::RTD_15_IC18_IMTQ, "RTD_15_IMTQ"},
}};
std::array<SpiCookie*, NUM_RTDS> rtdCookies = {};
std::array<Max31865EiveHandler*, NUM_RTDS> rtds = {};
RtdFdir* rtdFdir = nullptr;
for (uint8_t idx = 0; idx < NUMBER_RTDS; idx++) {
rtdCookies[idx] =
new SpiCookie(cookieArgs[idx].first, cookieArgs[idx].second, spiDev,
Max31865Definitions::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED);
rtds[idx] = new Max31865PT1000Handler(rtdIds[idx], objects::SPI_COM_IF, rtdCookies[idx]);
// Create special low level reader communication interface
new Max31865RtdReader(objects::SPI_RTD_COM_IF, comIF, gpioComIF);
for (uint8_t idx = 0; idx < NUM_RTDS; idx++) {
rtdCookies[idx] = new SpiCookie(cookieArgs[idx].first, cookieArgs[idx].second,
MAX31865::MAX_REPLY_SIZE, spi::RTD_MODE, spi::RTD_SPEED);
rtdCookies[idx]->setMutexParams(MutexIF::TimeoutType::WAITING, spi::RTD_CS_TIMEOUT);
Max31865ReaderCookie* rtdLowLevelCookie =
new Max31865ReaderCookie(rtdInfos[idx].first, idx, rtdInfos[idx].second, rtdCookies[idx]);
rtds[idx] =
new Max31865EiveHandler(rtdInfos[idx].first, objects::SPI_RTD_COM_IF, rtdLowLevelCookie);
rtds[idx]->setDeviceInfo(idx, rtdInfos[idx].second);
rtds[idx]->setParent(objects::TCS_BOARD_ASS);
rtdFdir = new RtdFdir(rtdIds[idx]);
rtdFdir = new RtdFdir(rtdInfos[idx].first);
rtds[idx]->setCustomFdir(rtdFdir);
rtds[idx]->setDeviceIdx(idx + 3);
#if OBSW_DEBUG_RTD == 1
rtds[idx]->setDebugMode(true, 5);
#endif
#if OBSW_TEST_RTD == 1
rtds[idx]->setInstantNormal(true);
rtds[idx]->setStartUpImmediately();
#endif
}
#if OBSW_TEST_RTD == 1
for (auto& rtd : rtds) {
if (rtd != nullptr) {
rtd->setStartUpImmediately();
rtd->setInstantNormal(true);
}
}
#endif // OBSW_TEST_RTD == 1
TcsBoardHelper helper(rtdIds);
TcsBoardHelper helper(rtdInfos);
TcsBoardAssembly* tcsBoardAss =
new TcsBoardAssembly(objects::TCS_BOARD_ASS, objects::NO_OBJECT, pwrSwitcher,
pcdu::Switches::PDU1_CH0_TCS_BOARD_3V3, helper);
static_cast<void>(tcsBoardAss);
#endif // OBSW_ADD_RTD_DEVICES == 1
}
void ObjectFactory::gpioChecker(ReturnValue_t result, std::string output) {
if (result != HasReturnvaluesIF::RETURN_OK) {
sif::error << "ObjectFactory: Adding GPIOs failed for " << output << std::endl;
}
}

View File

@ -1,5 +1,7 @@
#pragma once
#include <fsfw/returnvalues/HasReturnvaluesIF.h>
#include <string>
class GpioIF;
@ -10,6 +12,9 @@ namespace ObjectFactory {
void createSunSensorComponents(GpioIF* gpioComIF, SpiComIF* spiComIF, PowerSwitchIF* pwrSwitcher,
std::string spiDev);
void createRtdComponents(std::string spiDev, GpioIF* gpioComIF, PowerSwitchIF* pwrSwitcher);
void createRtdComponents(std::string spiDev, GpioIF* gpioComIF, PowerSwitchIF* pwrSwitcher,
SpiComIF* comIF);
void gpioChecker(ReturnValue_t result, std::string output);
} // namespace ObjectFactory

View File

@ -1,10 +1,2 @@
target_sources(${OBSW_NAME} PRIVATE
LibgpiodTest.cpp
I2cTestClass.cpp
SpiTestClass.cpp
UartTestClass.cpp
)
target_sources(${OBSW_NAME} PRIVATE LibgpiodTest.cpp I2cTestClass.cpp
SpiTestClass.cpp UartTestClass.cpp)

View File

@ -19,18 +19,18 @@ LibgpiodTest::LibgpiodTest(object_id_t objectId, object_id_t gpioIfobjectId, Gpi
LibgpiodTest::~LibgpiodTest() {}
ReturnValue_t LibgpiodTest::performPeriodicAction() {
int gpioState;
gpio::Levels gpioState;
ReturnValue_t result;
switch (testCase) {
case (TestCases::READ): {
result = gpioInterface->readGpio(gpioIds::TEST_ID_0, &gpioState);
result = gpioInterface->readGpio(gpioIds::TEST_ID_0, gpioState);
if (result != RETURN_OK) {
sif::warning << "LibgpiodTest::performPeriodicAction: Failed to read gpio " << std::endl;
return RETURN_FAILED;
} else {
sif::debug << "LibgpiodTest::performPeriodicAction: MIO 0 state = " << gpioState
<< std::endl;
sif::debug << "LibgpiodTest::performPeriodicAction: MIO 0 state = "
<< static_cast<int>(gpioState) << std::endl;
}
break;
}
@ -38,19 +38,19 @@ ReturnValue_t LibgpiodTest::performPeriodicAction() {
break;
}
case (TestCases::BLINK): {
result = gpioInterface->readGpio(gpioIds::TEST_ID_0, &gpioState);
result = gpioInterface->readGpio(gpioIds::TEST_ID_0, gpioState);
if (result != HasReturnvaluesIF::RETURN_OK) {
sif::warning << "LibgpiodTest::performPeriodicAction: Failed to read gpio " << std::endl;
return RETURN_FAILED;
}
if (gpioState == 1) {
if (gpioState == gpio::Levels::HIGH) {
result = gpioInterface->pullLow(gpioIds::TEST_ID_0);
if (result != HasReturnvaluesIF::RETURN_OK) {
sif::warning << "LibgpiodTest::performPeriodicAction: Could not pull GPIO low!"
<< std::endl;
return HasReturnvaluesIF::RETURN_FAILED;
}
} else if (gpioState == 0) {
} else if (gpioState == gpio::Levels::LOW) {
result = gpioInterface->pullHigh(gpioIds::TEST_ID_0);
if (result != HasReturnvaluesIF::RETURN_OK) {
sif::warning << "LibgpiodTest::performPeriodicAction: Could not pull GPIO high!"
@ -72,7 +72,7 @@ ReturnValue_t LibgpiodTest::performPeriodicAction() {
}
ReturnValue_t LibgpiodTest::performOneShotAction() {
int gpioState;
gpio::Levels gpioState;
ReturnValue_t result;
switch (testCase) {
@ -93,8 +93,8 @@ ReturnValue_t LibgpiodTest::performOneShotAction() {
<< std::endl;
return HasReturnvaluesIF::RETURN_OK;
}
result = gpioInterface->readGpio(gpioIds::TEST_ID_1, &gpioState);
if (result == HasReturnvaluesIF::RETURN_OK and gpioState == 1) {
result = gpioInterface->readGpio(gpioIds::TEST_ID_1, gpioState);
if (result == HasReturnvaluesIF::RETURN_OK and gpioState == gpio::Levels::HIGH) {
sif::info << "LibgpiodTest::performOneShotAction: "
"GPIO state read successfully and is high"
<< std::endl;
@ -110,8 +110,8 @@ ReturnValue_t LibgpiodTest::performOneShotAction() {
"GPIO pulled low successfully for loopback test"
<< std::endl;
}
result = gpioInterface->readGpio(gpioIds::TEST_ID_1, &gpioState);
if (result == HasReturnvaluesIF::RETURN_OK and gpioState == 0) {
result = gpioInterface->readGpio(gpioIds::TEST_ID_1, gpioState);
if (result == HasReturnvaluesIF::RETURN_OK and gpioState == gpio::Levels::LOW) {
sif::info << "LibgpiodTest::performOneShotAction: "
"GPIO state read successfully and is low"
<< std::endl;

View File

@ -70,8 +70,8 @@ void UartTestClass::gpsInit() {
/* Get file descriptor */
serialPort = open("/dev/serial0", O_RDWR);
if (serialPort < 0) {
sif::warning << "UartTestClass::gpsInit: open call failed with error [" << errno << ", " << strerror(errno)
<< std::endl;
sif::warning << "UartTestClass::gpsInit: open call failed with error [" << errno << ", "
<< strerror(errno) << std::endl;
}
/* Setting up UART parameters */
tty.c_cflag &= ~PARENB; // Clear parity bit
@ -99,8 +99,8 @@ void UartTestClass::gpsInit() {
cfsetispeed(&tty, B9600);
cfsetospeed(&tty, B9600);
if (tcsetattr(serialPort, TCSANOW, &tty) != 0) {
sif::warning << "UartTestClass::gpsInit: tcsetattr call failed with error [" << errno << ", " << strerror(errno)
<< std::endl;
sif::warning << "UartTestClass::gpsInit: tcsetattr call failed with error [" << errno << ", "
<< strerror(errno) << std::endl;
;
}
// Flush received and unread data. Those are old NMEA strings which are not relevant anymore
@ -115,8 +115,8 @@ void UartTestClass::gpsPeriodic() {
bytesRead = read(serialPort, reinterpret_cast<void*>(recBuf.data()),
static_cast<unsigned int>(recBuf.size()));
if (bytesRead < 0) {
sif::warning << "UartTestClass::gpsPeriodic: read call failed with error [" << errno
<< ", " << strerror(errno) << "]" << std::endl;
sif::warning << "UartTestClass::gpsPeriodic: read call failed with error [" << errno << ", "
<< strerror(errno) << "]" << std::endl;
break;
} else if (bytesRead >= static_cast<int>(recBuf.size())) {
sif::debug << "UartTestClass::gpsPeriodic: "
@ -268,8 +268,8 @@ void UartTestClass::scexSimpleInit() {
/* Get file descriptor */
serialPort = open(devname.c_str(), O_RDWR);
if (serialPort < 0) {
sif::warning << "UartTestClass::scexSimpleInit: Open call failed with error [" << errno << ", " << strerror(errno)
<< std::endl;
sif::warning << "UartTestClass::scexSimpleInit: Open call failed with error [" << errno << ", "
<< strerror(errno) << std::endl;
return;
}
// Setting up UART parameters
@ -296,8 +296,8 @@ void UartTestClass::scexSimpleInit() {
#endif
if (tcsetattr(serialPort, TCSANOW, &tty) != 0) {
sif::warning << "UartTestClass::scexSimpleInit: tcsetattr call failed with error [" << errno << ", " << strerror(errno)
<< std::endl;
sif::warning << "UartTestClass::scexSimpleInit: tcsetattr call failed with error [" << errno
<< ", " << strerror(errno) << std::endl;
}
// Flush received and unread data
tcflush(serialPort, TCIOFLUSH);
@ -323,7 +323,9 @@ void UartTestClass::scexSimplePeriodic() {
};
size_t bytesWritten = write(serialPort, cmdBuf.data(), encodedLen);
if (bytesWritten != encodedLen) {
sif::warning << "UartTestClass::scexSimplePeriodic: Sending command to solar experiment failed" << std::endl;
sif::warning
<< "UartTestClass::scexSimplePeriodic: Sending command to solar experiment failed"
<< std::endl;
}
cmdSent = true;
cmdDone = false;
@ -335,10 +337,11 @@ void UartTestClass::scexSimplePeriodic() {
bytesRead = read(serialPort, reinterpret_cast<void*>(recBuf.data()),
static_cast<unsigned int>(recBuf.size()));
if (bytesRead == 0) {
sif::warning << "UartTestClass::scexSimplePeriodic: Reading SCEX: Timeout or no bytes read" << std::endl;
sif::warning << "UartTestClass::scexSimplePeriodic: Reading SCEX: Timeout or no bytes read"
<< std::endl;
} else if (bytesRead < 0) {
sif::warning << "UartTestClass::scexSimplePeriodic: read call failed with error ["
<< errno << ", " << strerror(errno) << "]" << std::endl;
sif::warning << "UartTestClass::scexSimplePeriodic: read call failed with error [" << errno
<< ", " << strerror(errno) << "]" << std::endl;
break;
} else if (bytesRead >= static_cast<int>(recBuf.size())) {
sif::debug << "UartTestClass::scexSimplePeriodic: recv buffer might not be large "
@ -383,7 +386,8 @@ void UartTestClass::foundDlePacketHandler(const DleParser::Context& ctx) {
}
void UartTestClass::handleFoundDlePacket(uint8_t* packet, size_t len) {
sif::info << "UartTestClass::handleFoundDlePacket: Detected DLE encoded packet with decoded size " << len << std::endl;
sif::info << "UartTestClass::handleFoundDlePacket: Detected DLE encoded packet with decoded size "
<< len << std::endl;
}
std::string UartTestClass::random_string(std::string::size_type length) {

View File

@ -1,3 +1 @@
target_sources(${OBSW_NAME} PRIVATE
gpioCallbacks.cpp
)
target_sources(${OBSW_NAME} PRIVATE gpioCallbacks.cpp)

View File

@ -1,8 +1 @@
target_sources(${OBSW_NAME} PUBLIC
CspComIF.cpp
CspCookie.cpp
)
target_sources(${OBSW_NAME} PUBLIC CspComIF.cpp CspCookie.cpp)

View File

@ -1,13 +1,10 @@
if(EIVE_BUILD_GPSD_GPS_HANDLER)
target_sources(${OBSW_NAME} PRIVATE
GPSHyperionLinuxController.cpp
)
target_sources(${OBSW_NAME} PRIVATE GPSHyperionLinuxController.cpp)
endif()
target_sources(${OBSW_NAME} PRIVATE
ScexUartReader.cpp
ScexDleParser.cpp
ScexHelper.cpp
)
target_sources(
${OBSW_NAME} PRIVATE Max31865RtdLowlevelHandler.cpp ScexUartReader.cpp
ScexDleParser.cpp ScexHelper.cpp)
add_subdirectory(ploc)
add_subdirectory(startracker)

View File

@ -1,6 +1,9 @@
#include "GPSHyperionLinuxController.h"
#include <fsfw/timemanager/Stopwatch.h>
#include "OBSWConfig.h"
#include "fsfw/FSFW.h"
#include "fsfw/datapool/PoolReadGuard.h"
#include "fsfw/timemanager/Clock.h"
#include "linux/utility/utility.h"
@ -17,12 +20,14 @@ GPSHyperionLinuxController::GPSHyperionLinuxController(object_id_t objectId, obj
bool debugHyperionGps)
: ExtendedControllerBase(objectId, objects::NO_OBJECT),
gpsSet(this),
myGpsmm(GPSD_SHARED_MEMORY, nullptr),
debugHyperionGps(debugHyperionGps) {
timeUpdateCd.resetTimer();
}
GPSHyperionLinuxController::~GPSHyperionLinuxController() {}
GPSHyperionLinuxController::~GPSHyperionLinuxController() {
gps_stream(&gps, WATCH_DISABLE, nullptr);
gps_close(&gps);
}
void GPSHyperionLinuxController::performControlOperation() {
#ifdef FSFW_OSAL_LINUX
@ -36,6 +41,7 @@ ReturnValue_t GPSHyperionLinuxController::checkModeCommand(Mode_t mode, Submode_
uint32_t *msToReachTheMode) {
if (not modeCommanded) {
if (mode == MODE_ON or mode == MODE_OFF) {
gpsNotOpenSwitch = true;
// 5h time to reach fix
*msToReachTheMode = MAX_SECONDS_TO_REACH_FIX;
maxTimeToReachFix.resetTimer();
@ -51,12 +57,12 @@ ReturnValue_t GPSHyperionLinuxController::executeAction(ActionId_t actionId,
MessageQueueId_t commandedBy,
const uint8_t *data, size_t size) {
switch (actionId) {
case (GpsHyperion::TRIGGER_RESET_PIN): {
case (GpsHyperion::TRIGGER_RESET_PIN_GNSS): {
if (resetCallback != nullptr) {
PoolReadGuard pg(&gpsSet);
// Set HK entries invalid
gpsSet.setValidity(false, true);
resetCallback(resetCallbackArgs);
resetCallback(data, size, resetCallbackArgs);
return HasActionsIF::EXECUTION_FINISHED;
}
return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED;
@ -96,6 +102,27 @@ ReturnValue_t GPSHyperionLinuxController::initialize() {
if (result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
auto openError = [&](const char *type, int error) {
if (gpsNotOpenSwitch) {
// Opening failed
#if FSFW_VERBOSE_LEVEL >= 1
sif::warning << "GPSHyperionHandler::readGpsDataFromGpsd: Opening GPSMM " << type
<< " failed | Error " << error << " | " << gps_errstr(error) << std::endl;
#endif
gpsNotOpenSwitch = false;
}
};
if (readMode == ReadModes::SOCKET) {
int retval = gps_open("localhost", DEFAULT_GPSD_PORT, &gps);
if (retval != 0) {
openError("Socket", retval);
}
} else if (readMode == ReadModes::SHM) {
int retval = gps_open(GPSD_SHARED_MEMORY, "", &gps);
if (retval != 0) {
openError("SHM", retval);
}
}
return result;
}
@ -104,33 +131,64 @@ ReturnValue_t GPSHyperionLinuxController::handleCommandMessage(CommandMessage *m
}
#ifdef FSFW_OSAL_LINUX
void GPSHyperionLinuxController::readGpsDataFromGpsd() {
// The data from the device will generally be read all at once. Therefore, we
// can set all field here
if (not myGpsmm.is_open()) {
// Opening failed
#if FSFW_VERBOSE_LEVEL >= 1
sif::warning << "GPSHyperionHandler::readGpsDataFromGpsd: Opening GPSMM failed" << std::endl;
#endif
}
gps_data_t *gps = nullptr;
gps = myGpsmm.read();
if (gps == nullptr) {
sif::warning << "GPSHyperionHandler::readGpsDataFromGpsd: Reading GPS data failed" << std::endl;
return;
auto readError = [&](int error) {
if (gpsReadFailedSwitch) {
gpsReadFailedSwitch = false;
sif::warning << "GPSHyperionHandler::readGpsDataFromGpsd: Reading GPS data failed | "
"Error "
<< error << " | " << gps_errstr(error) << std::endl;
}
};
currentClientBuf = gps_data(&gps);
if (readMode == ReadModes::SOCKET) {
gps_stream(&gps, WATCH_ENABLE | WATCH_JSON, nullptr);
// Exit if no data is seen in 2 seconds (should not happen)
if (not gps_waiting(&gps, 2000000)) {
return;
}
int result = gps_read(&gps);
if (result == -1) {
readError(result);
return;
}
if (MODE_SET != (MODE_SET & gps.set)) {
if (noModeSetCntr >= 0) {
noModeSetCntr++;
}
if (noModeSetCntr == 10) {
// TODO: Trigger event here
sif::warning << "GPSHyperionHandler::readGpsDataFromGpsd: No mode could be "
"read for 10 consecutive reads"
<< std::endl;
noModeSetCntr = -1;
}
}
noModeSetCntr = 0;
} else if (readMode == ReadModes::SHM) {
int result = gps_read(&gps);
if (result == -1) {
readError(result);
return;
}
}
handleGpsRead();
}
ReturnValue_t GPSHyperionLinuxController::handleGpsRead() {
PoolReadGuard pg(&gpsSet);
if (pg.getReadResult() != HasReturnvaluesIF::RETURN_OK) {
#if FSFW_VERBOSE_LEVEL >= 1
sif::warning << "GPSHyperionHandler::readGpsDataFromGpsd: Reading dataset failed" << std::endl;
#endif
return;
return RETURN_FAILED;
}
bool validFix = false;
static_cast<void>(validFix);
// 0: Not seen, 1: No fix, 2: 2D-Fix, 3: 3D-Fix
int newFixMode = gps->fix.mode;
int newFixMode = gps.fix.mode;
if (newFixMode == 2 or newFixMode == 3) {
validFix = true;
}
@ -138,7 +196,7 @@ void GPSHyperionLinuxController::readGpsDataFromGpsd() {
triggerEvent(GpsHyperion::GPS_FIX_CHANGE, gpsSet.fixMode.value, newFixMode);
}
gpsSet.fixMode.value = newFixMode;
if (gps->fix.mode == 0 or gps->fix.mode == 1) {
if (gps.fix.mode == 0 or gps.fix.mode == 1) {
if (modeCommanded and maxTimeToReachFix.hasTimedOut()) {
// We are supposed to be on and functioning, but not fix was found
if (mode == MODE_ON or mode == MODE_NORMAL) {
@ -147,43 +205,52 @@ void GPSHyperionLinuxController::readGpsDataFromGpsd() {
modeCommanded = false;
}
gpsSet.setValidity(false, true);
} else if (gps->satellites_used > 0) {
} else if (gps.satellites_used > 0) {
gpsSet.setValidity(true, true);
}
gpsSet.satInUse.value = gps->satellites_used;
gpsSet.satInView.value = gps->satellites_visible;
gpsSet.satInUse.value = gps.satellites_used;
gpsSet.satInView.value = gps.satellites_visible;
if (std::isfinite(gps->fix.latitude)) {
if (std::isfinite(gps.fix.latitude)) {
// Negative latitude -> South direction
gpsSet.latitude.value = gps->fix.latitude;
gpsSet.latitude.value = gps.fix.latitude;
} else {
gpsSet.latitude.setValid(false);
}
if (std::isfinite(gps->fix.longitude)) {
if (std::isfinite(gps.fix.longitude)) {
// Negative longitude -> West direction
gpsSet.longitude.value = gps->fix.longitude;
gpsSet.longitude.value = gps.fix.longitude;
} else {
gpsSet.longitude.setValid(false);
}
if (std::isfinite(gps->fix.altitude)) {
gpsSet.altitude.value = gps->fix.altitude;
if (std::isfinite(gps.fix.altitude)) {
gpsSet.altitude.value = gps.fix.altitude;
} else {
gpsSet.altitude.setValid(false);
}
if (std::isfinite(gps->fix.speed)) {
gpsSet.speed.value = gps->fix.speed;
if (std::isfinite(gps.fix.speed)) {
gpsSet.speed.value = gps.fix.speed;
} else {
gpsSet.speed.setValid(false);
}
gpsSet.unixSeconds.value = gps->fix.time.tv_sec;
#if LIBGPS_VERSION_MINOR <= 17
gpsSet.unixSeconds.value = gps.fix.time;
#else
gpsSet.unixSeconds.value = gps.fix.time.tv_sec;
#endif
timeval time = {};
time.tv_sec = gpsSet.unixSeconds.value;
time.tv_usec = gps->fix.time.tv_nsec / 1000;
#if LIBGPS_VERSION_MINOR <= 17
double fractionalPart = gps.fix.time - std::floor(gps.fix.time);
time.tv_usec = fractionalPart * 1000.0 * 1000.0;
#else
time.tv_usec = gps.fix.time.tv_nsec / 1000;
#endif
std::time_t t = std::time(nullptr);
if (time.tv_sec == t) {
timeIsConstantCounter++;
@ -222,19 +289,29 @@ void GPSHyperionLinuxController::readGpsDataFromGpsd() {
gpsSet.seconds = timeOfDay.second;
if (debugHyperionGps) {
sif::info << "-- Hyperion GPS Data --" << std::endl;
time_t timeRaw = gps->fix.time.tv_sec;
#if LIBGPS_VERSION_MINOR <= 17
time_t timeRaw = gps.fix.time;
#else
time_t timeRaw = gps.fix.time.tv_sec;
#endif
std::tm *time = gmtime(&timeRaw);
std::cout << "Time: " << std::put_time(time, "%c %Z") << std::endl;
std::cout << "Visible satellites: " << gps->satellites_visible << std::endl;
std::cout << "Satellites used: " << gps->satellites_used << std::endl;
std::cout << "Fix (0:Not Seen|1:No Fix|2:2D|3:3D): " << gps->fix.mode << std::endl;
std::cout << "Latitude: " << gps->fix.latitude << std::endl;
std::cout << "Longitude: " << gps->fix.longitude << std::endl;
std::cout << "Altitude(MSL): " << gps->fix.altMSL << std::endl;
std::cout << "Speed(m/s): " << gps->fix.speed << std::endl;
std::cout << "Visible satellites: " << gps.satellites_visible << std::endl;
std::cout << "Satellites used: " << gps.satellites_used << std::endl;
std::cout << "Fix (0:Not Seen|1:No Fix|2:2D|3:3D): " << gps.fix.mode << std::endl;
std::cout << "Latitude: " << gps.fix.latitude << std::endl;
std::cout << "Longitude: " << gps.fix.longitude << std::endl;
#if LIBGPS_VERSION_MINOR <= 17
std::cout << "Altitude(MSL): " << gps.fix.altitude << std::endl;
#else
std::cout << "Altitude(MSL): " << gps.fix.altMSL << std::endl;
#endif
std::cout << "Speed(m/s): " << gps.fix.speed << std::endl;
std::time_t t = std::time(nullptr);
std::tm tm = *std::gmtime(&t);
std::cout << "C Time: " << std::put_time(&tm, "%c") << std::endl;
}
return RETURN_OK;
}
#endif

View File

@ -24,11 +24,13 @@ class GPSHyperionLinuxController : public ExtendedControllerBase {
public:
static constexpr uint32_t MAX_SECONDS_TO_REACH_FIX = 60 * 60 * 5;
enum ReadModes { SHM = 0, SOCKET = 1 };
GPSHyperionLinuxController(object_id_t objectId, object_id_t parentId,
bool debugHyperionGps = false);
virtual ~GPSHyperionLinuxController();
using gpioResetFunction_t = ReturnValue_t (*)(void* args);
using gpioResetFunction_t = ReturnValue_t (*)(const uint8_t* actionData, size_t len, void* args);
void setResetPinTriggerFunction(gpioResetFunction_t resetCallback, void* args);
ReturnValue_t handleCommandMessage(CommandMessage* message) override;
@ -47,13 +49,20 @@ class GPSHyperionLinuxController : public ExtendedControllerBase {
ReturnValue_t initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
LocalDataPoolManager& poolManager) override;
ReturnValue_t handleGpsRead();
private:
GpsPrimaryDataset gpsSet;
gps_data_t gps = {};
const char* currentClientBuf = nullptr;
ReadModes readMode = ReadModes::SOCKET;
Countdown maxTimeToReachFix = Countdown(MAX_SECONDS_TO_REACH_FIX * 1000);
bool modeCommanded = true;
bool timeInit = true;
gpsmm myGpsmm;
bool gpsNotOpenSwitch = true;
bool gpsReadFailedSwitch = true;
bool debugHyperionGps = false;
int32_t noModeSetCntr = 0;
uint32_t timeIsConstantCounter = 0;
Countdown timeUpdateCd = Countdown(60);

View File

@ -0,0 +1,465 @@
#include "Max31865RtdLowlevelHandler.h"
#include <fsfw/tasks/TaskFactory.h>
#include <fsfw/timemanager/Stopwatch.h>
#include <fsfw_hal/linux/spi/ManualCsLockGuard.h>
#define OBSW_RTD_AUTO_MODE 1
#if OBSW_RTD_AUTO_MODE == 1
static constexpr uint8_t BASE_CFG = (MAX31865::Bias::ON << MAX31865::CfgBitPos::BIAS_SEL) |
(MAX31865::Wires::FOUR_WIRE << MAX31865::CfgBitPos::WIRE_SEL) |
(MAX31865::ConvMode::AUTO << MAX31865::CfgBitPos::CONV_MODE);
#else
static constexpr uint8_t BASE_CFG =
(MAX31865::Bias::OFF << MAX31865::CfgBitPos::BIAS_SEL) |
(MAX31865::Wires::FOUR_WIRE << MAX31865::CfgBitPos::WIRE_SEL) |
(MAX31865::ConvMode::NORM_OFF << MAX31865::CfgBitPos::CONV_MODE);
#endif
Max31865RtdReader::Max31865RtdReader(object_id_t objectId, SpiComIF* lowLevelComIF, GpioIF* gpioIF)
: SystemObject(objectId), rtds(EiveMax31855::NUM_RTDS), comIF(lowLevelComIF), gpioIF(gpioIF) {
readerMutex = MutexFactory::instance()->createMutex();
}
ReturnValue_t Max31865RtdReader::performOperation(uint8_t operationCode) {
using namespace MAX31865;
ReturnValue_t result = RETURN_OK;
static_cast<void>(result);
// Stopwatch watch;
if (periodicInitHandling()) {
#if OBSW_RTD_AUTO_MODE == 0
// 10 ms delay for VBIAS startup
TaskFactory::delayTask(10);
#endif
} else {
// No devices usable (e.g. TCS board off)
return RETURN_OK;
}
#if OBSW_RTD_AUTO_MODE == 0
result = periodicReadReqHandling();
if (result != RETURN_OK) {
return result;
}
// After requesting, 65 milliseconds delay required
TaskFactory::delayTask(65);
#endif
return periodicReadHandling();
}
bool Max31865RtdReader::rtdIsActive(uint8_t idx) {
if (rtds[idx]->on and rtds[idx]->active and rtds[idx]->configured) {
return true;
}
return false;
}
bool Max31865RtdReader::periodicInitHandling() {
using namespace MAX31865;
MutexGuard mg(readerMutex);
ReturnValue_t result = RETURN_OK;
if (mg.getLockResult() != RETURN_OK) {
sif::warning << "Max31865RtdReader::periodicInitHandling: Mutex lock failed" << std::endl;
return false;
}
for (auto& rtd : rtds) {
if (rtd == nullptr) {
continue;
}
if ((rtd->on or rtd->active) and not rtd->configured and rtd->cd.hasTimedOut()) {
ManualCsLockWrapper mg(csLock, gpioIF, rtd->spiCookie, csTimeoutType, csTimeoutMs);
if (mg.lockResult != RETURN_OK or mg.gpioResult != RETURN_OK) {
sif::error << "Max31865RtdReader::periodicInitHandling: Manual CS lock failed" << std::endl;
break;
}
result = writeCfgReg(rtd->spiCookie, BASE_CFG);
if (result != HasReturnvaluesIF::RETURN_OK) {
handleSpiError(rtd, result, "writeCfgReg");
}
if (rtd->writeLowThreshold) {
result = writeLowThreshold(rtd->spiCookie, rtd->lowThreshold);
if (result != HasReturnvaluesIF::RETURN_OK) {
handleSpiError(rtd, result, "writeLowThreshold");
}
}
if (rtd->writeHighThreshold) {
result = writeHighThreshold(rtd->spiCookie, rtd->highThreshold);
if (result != HasReturnvaluesIF::RETURN_OK) {
handleSpiError(rtd, result, "writeHighThreshold");
}
}
result = clearFaultStatus(rtd->spiCookie);
if (result != HasReturnvaluesIF::RETURN_OK) {
handleSpiError(rtd, result, "clearFaultStatus");
}
rtd->configured = true;
rtd->db.configured = true;
if (rtd->active) {
rtd->db.active = true;
}
}
if (rtd->active and rtd->configured and not rtd->db.active) {
rtd->db.active = true;
}
}
bool someRtdUsable = false;
for (auto& rtd : rtds) {
if (rtd == nullptr) {
continue;
}
if (rtdIsActive(rtd->idx)) {
#if OBSW_RTD_AUTO_MODE == 0
result = writeBiasSel(Bias::ON, rtd->spiCookie, BASE_CFG);
#endif
someRtdUsable = true;
}
}
return someRtdUsable;
}
ReturnValue_t Max31865RtdReader::periodicReadReqHandling() {
using namespace MAX31865;
MutexGuard mg(readerMutex);
if (mg.getLockResult() != RETURN_OK) {
sif::warning << "Max31865RtdReader::periodicReadReqHandling: Mutex lock failed" << std::endl;
return RETURN_FAILED;
}
// Now request one shot config for all active RTDs
for (auto& rtd : rtds) {
if (rtd == nullptr) {
continue;
}
if (rtdIsActive(rtd->idx)) {
ReturnValue_t result = writeCfgReg(rtd->spiCookie, BASE_CFG | (1 << CfgBitPos::ONE_SHOT));
if (result != RETURN_OK) {
handleSpiError(rtd, result, "writeCfgReg");
// Release mutex ASAP
return RETURN_FAILED;
}
}
}
return RETURN_OK;
}
ReturnValue_t Max31865RtdReader::periodicReadHandling() {
using namespace MAX31865;
auto result = RETURN_OK;
MutexGuard mg(readerMutex);
if (mg.getLockResult() != RETURN_OK) {
sif::warning << "Max31865RtdReader::periodicReadReqHandling: Mutex lock failed" << std::endl;
return RETURN_FAILED;
}
// Now read the RTD values
for (auto& rtd : rtds) {
if (rtd == nullptr) {
continue;
}
if (rtdIsActive(rtd->idx)) {
uint16_t rtdVal = 0;
bool faultBitSet = false;
result = readRtdVal(rtd->spiCookie, rtdVal, faultBitSet);
if (result != RETURN_OK) {
handleSpiError(rtd, result, "readRtdVal");
return RETURN_FAILED;
}
if (faultBitSet) {
rtd->db.faultBitSet = faultBitSet;
}
rtd->db.adcCode = rtdVal;
}
}
#if OBSW_RTD_AUTO_MODE == 0
for (auto& rtd : rtds) {
if (rtd == nullptr) {
continue;
}
// Even if a device was made inactive, turn off the bias here. If it was turned off, not
// necessary anymore..
if (rtd->on) {
result = writeBiasSel(Bias::OFF, rtd->spiCookie, BASE_CFG);
}
}
#endif
return RETURN_OK;
}
ReturnValue_t Max31865RtdReader::initializeInterface(CookieIF* cookie) {
if (cookie == nullptr) {
throw std::invalid_argument("Invalid MAX31865 Reader Cookie");
}
auto* rtdCookie = dynamic_cast<Max31865ReaderCookie*>(cookie);
ReturnValue_t result = comIF->initializeInterface(rtdCookie->spiCookie);
if (result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
if (rtdCookie->idx > EiveMax31855::NUM_RTDS) {
throw std::invalid_argument("Invalid RTD index");
}
rtds[rtdCookie->idx] = rtdCookie;
MutexGuard mg(readerMutex);
if (dbLen == 0) {
dbLen = rtdCookie->db.getSerializedSize();
}
return RETURN_OK;
}
ReturnValue_t Max31865RtdReader::sendMessage(CookieIF* cookie, const uint8_t* sendData,
size_t sendLen) {
if (cookie == nullptr) {
return RETURN_FAILED;
}
// Empty command.. don't fail for now
if (sendLen < 1) {
return RETURN_OK;
}
MutexGuard mg(readerMutex);
if (mg.getLockResult() != RETURN_OK) {
sif::warning << "Max31865RtdReader::sendMessage: Mutex lock failed" << std::endl;
return RETURN_FAILED;
}
auto* rtdCookie = dynamic_cast<Max31865ReaderCookie*>(cookie);
uint8_t cmdRaw = sendData[0];
if (cmdRaw > EiveMax31855::RtdCommands::NUM_CMDS) {
sif::warning << "Max31865RtdReader::sendMessage: Invalid command" << std::endl;
return RETURN_FAILED;
}
auto thresholdHandler = [](Max31865ReaderCookie* rtdCookie, const uint8_t* sendData) {
rtdCookie->lowThreshold = (sendData[1] << 8) | sendData[2];
rtdCookie->highThreshold = (sendData[3] << 8) | sendData[4];
rtdCookie->writeLowThreshold = true;
rtdCookie->writeHighThreshold = true;
};
auto cmd = static_cast<EiveMax31855::RtdCommands>(sendData[0]);
switch (cmd) {
case (EiveMax31855::RtdCommands::ON): {
if (not rtdCookie->on) {
rtdCookie->cd.setTimeout(MAX31865::WARMUP_MS);
rtdCookie->cd.resetTimer();
rtdCookie->on = true;
rtdCookie->active = false;
rtdCookie->configured = false;
if (sendLen == 5) {
thresholdHandler(rtdCookie, sendData);
}
}
break;
}
case (EiveMax31855::RtdCommands::ACTIVE): {
if (not rtdCookie->on) {
rtdCookie->cd.setTimeout(MAX31865::WARMUP_MS);
rtdCookie->cd.resetTimer();
rtdCookie->on = true;
rtdCookie->active = true;
rtdCookie->configured = false;
} else {
rtdCookie->active = true;
}
if (sendLen == 5) {
thresholdHandler(rtdCookie, sendData);
}
break;
}
case (EiveMax31855::RtdCommands::OFF): {
rtdCookie->on = false;
rtdCookie->active = false;
rtdCookie->configured = false;
break;
}
case (EiveMax31855::RtdCommands::HIGH_TRESHOLD): {
if (sendLen == 3) {
rtdCookie->highThreshold = (sendData[1] << 8) | sendData[2];
rtdCookie->writeHighThreshold = true;
} else {
return RETURN_FAILED;
}
break;
}
case (EiveMax31855::RtdCommands::LOW_THRESHOLD): {
if (sendLen == 3) {
rtdCookie->lowThreshold = (sendData[1] << 8) | sendData[2];
rtdCookie->writeLowThreshold = true;
} else {
return RETURN_FAILED;
}
break;
}
case (EiveMax31855::RtdCommands::CFG):
default: {
// TODO: Only implement if needed
break;
}
}
return RETURN_OK;
}
ReturnValue_t Max31865RtdReader::getSendSuccess(CookieIF* cookie) { return RETURN_OK; }
ReturnValue_t Max31865RtdReader::requestReceiveMessage(CookieIF* cookie, size_t requestLen) {
return RETURN_OK;
}
ReturnValue_t Max31865RtdReader::readReceivedMessage(CookieIF* cookie, uint8_t** buffer,
size_t* size) {
MutexGuard mg(readerMutex);
if (mg.getLockResult() != RETURN_OK) {
// TODO: Emit warning
return RETURN_FAILED;
}
auto* rtdCookie = dynamic_cast<Max31865ReaderCookie*>(cookie);
uint8_t* exchangePtr = rtdCookie->exchangeBuf.data();
size_t serLen = 0;
auto result = rtdCookie->db.serialize(&exchangePtr, &serLen, rtdCookie->exchangeBuf.size(),
SerializeIF::Endianness::MACHINE);
if (result != RETURN_OK) {
// TODO: Emit warning
return RETURN_FAILED;
}
*buffer = reinterpret_cast<uint8_t*>(rtdCookie->exchangeBuf.data());
*size = serLen;
return RETURN_OK;
}
ReturnValue_t Max31865RtdReader::writeCfgReg(SpiCookie* cookie, uint8_t cfg) {
using namespace MAX31865;
return writeNToReg(cookie, CONFIG, 1, &cfg, nullptr);
}
ReturnValue_t Max31865RtdReader::writeBiasSel(MAX31865::Bias bias, SpiCookie* cookie,
uint8_t baseCfg) {
using namespace MAX31865;
if (bias == MAX31865::Bias::OFF) {
baseCfg &= ~(1 << CfgBitPos::BIAS_SEL);
} else {
baseCfg |= (1 << CfgBitPos::BIAS_SEL);
}
return writeCfgReg(cookie, baseCfg);
}
ReturnValue_t Max31865RtdReader::clearFaultStatus(SpiCookie* cookie) {
using namespace MAX31865;
// Read back the current configuration to avoid overwriting it when clearing te fault status
uint8_t currentCfg = 0;
auto result = readCfgReg(cookie, currentCfg);
if (result != RETURN_OK) {
return result;
}
// Clear bytes 5, 3 and 2 which need to be 0
currentCfg &= ~0x2C;
currentCfg |= (1 << CfgBitPos::FAULT_STATUS_CLEAR);
return writeCfgReg(cookie, currentCfg);
}
ReturnValue_t Max31865RtdReader::readCfgReg(SpiCookie* cookie, uint8_t& cfg) {
using namespace MAX31865;
uint8_t* replyPtr = nullptr;
auto result = readNFromReg(cookie, CONFIG, 1, &replyPtr);
if (result == RETURN_OK) {
cfg = replyPtr[0];
}
return result;
}
ReturnValue_t Max31865RtdReader::writeLowThreshold(SpiCookie* cookie, uint16_t val) {
using namespace MAX31865;
uint8_t cmd[2] = {static_cast<uint8_t>((val >> 8) & 0xff), static_cast<uint8_t>(val & 0xff)};
return writeNToReg(cookie, LOW_THRESHOLD, 2, cmd, nullptr);
}
ReturnValue_t Max31865RtdReader::writeHighThreshold(SpiCookie* cookie, uint16_t val) {
using namespace MAX31865;
uint8_t cmd[2] = {static_cast<uint8_t>((val >> 8) & 0xff), static_cast<uint8_t>(val & 0xff)};
return writeNToReg(cookie, HIGH_THRESHOLD, 2, cmd, nullptr);
}
ReturnValue_t Max31865RtdReader::readLowThreshold(SpiCookie* cookie, uint16_t& lowThreshold) {
using namespace MAX31865;
uint8_t* replyPtr = nullptr;
auto result = readNFromReg(cookie, LOW_THRESHOLD, 2, &replyPtr);
if (result == RETURN_OK) {
lowThreshold = (replyPtr[0] << 8) | replyPtr[1];
}
return result;
}
ReturnValue_t Max31865RtdReader::readHighThreshold(SpiCookie* cookie, uint16_t& highThreshold) {
using namespace MAX31865;
uint8_t* replyPtr = nullptr;
auto result = readNFromReg(cookie, HIGH_THRESHOLD, 2, &replyPtr);
if (result == RETURN_OK) {
highThreshold = (replyPtr[0] << 8) | replyPtr[1];
}
return result;
}
ReturnValue_t Max31865RtdReader::writeNToReg(SpiCookie* cookie, uint8_t reg, size_t n, uint8_t* cmd,
uint8_t** reply) {
using namespace MAX31865;
if (n > cmdBuf.size() - 1) {
return HasReturnvaluesIF::RETURN_FAILED;
}
cmdBuf[0] = reg | WRITE_BIT;
for (size_t idx = 0; idx < n; idx++) {
cmdBuf[idx + 1] = cmd[idx];
}
return comIF->sendMessage(cookie, cmdBuf.data(), n + 1);
}
ReturnValue_t Max31865RtdReader::readRtdVal(SpiCookie* cookie, uint16_t& val, bool& faultBitSet) {
using namespace MAX31865;
uint8_t* replyPtr = nullptr;
auto result = readNFromReg(cookie, RTD, 2, &replyPtr);
if (result != RETURN_OK) {
return result;
}
if (replyPtr[1] & 0b0000'0001) {
faultBitSet = true;
}
// Shift 1 to the right to remove fault bit
val = ((replyPtr[0] << 8) | replyPtr[1]) >> 1;
return result;
}
ReturnValue_t Max31865RtdReader::readNFromReg(SpiCookie* cookie, uint8_t reg, size_t n,
uint8_t** reply) {
using namespace MAX31865;
if (n > 4) {
return HasReturnvaluesIF::RETURN_FAILED;
}
// Clear write bit in any case
reg &= ~WRITE_BIT;
cmdBuf[0] = reg;
std::memset(cmdBuf.data() + 1, 0, n);
ReturnValue_t result = comIF->sendMessage(cookie, cmdBuf.data(), n + 1);
if (result != RETURN_OK) {
return RETURN_FAILED;
}
size_t dummyLen = 0;
uint8_t* replyPtr = nullptr;
result = comIF->readReceivedMessage(cookie, &replyPtr, &dummyLen);
if (result != RETURN_OK) {
return result;
}
if (reply != nullptr) {
*reply = replyPtr + 1;
}
return RETURN_OK;
}
ReturnValue_t Max31865RtdReader::handleSpiError(Max31865ReaderCookie* cookie, ReturnValue_t result,
const char* ctx) {
cookie->db.spiErrorCount.value += 1;
sif::warning << "Max31865RtdReader::handleSpiError: " << ctx << " | Failed with result " << result
<< std::endl;
return result;
}
ReturnValue_t Max31865RtdReader::initialize() {
csLock = comIF->getCsMutex();
return SystemObject::initialize();
}

View File

@ -0,0 +1,87 @@
#ifndef LINUX_DEVICES_MAX31865RTDREADER_H_
#define LINUX_DEVICES_MAX31865RTDREADER_H_
#include <fsfw/ipc/MutexIF.h>
#include <fsfw/tasks/ExecutableObjectIF.h>
#include <fsfw_hal/linux/spi/SpiComIF.h>
#include <fsfw_hal/linux/spi/SpiCookie.h>
#include "fsfw/devicehandlers/DeviceCommunicationIF.h"
#include "mission/devices/devicedefinitions/Max31865Definitions.h"
struct Max31865ReaderCookie : public CookieIF {
Max31865ReaderCookie(){};
Max31865ReaderCookie(object_id_t handlerId_, uint8_t idx_, const std::string& locString_,
SpiCookie* spiCookie_)
: idx(idx_), handlerId(handlerId_), locString(locString_), spiCookie(spiCookie_) {}
uint8_t idx = 0;
object_id_t handlerId = objects::NO_OBJECT;
std::string locString = "";
std::array<uint8_t, 12> exchangeBuf{};
Countdown cd = Countdown(MAX31865::WARMUP_MS);
bool on = false;
bool configured = false;
bool active = false;
bool writeLowThreshold = false;
bool writeHighThreshold = false;
uint16_t lowThreshold = 0;
uint16_t highThreshold = 0;
SpiCookie* spiCookie = nullptr;
// Exchange data buffer struct
EiveMax31855::ReadOutStruct db;
};
class Max31865RtdReader : public SystemObject,
public ExecutableObjectIF,
public DeviceCommunicationIF {
public:
Max31865RtdReader(object_id_t objectId, SpiComIF* lowLevelComIF, GpioIF* gpioIF);
ReturnValue_t performOperation(uint8_t operationCode) override;
ReturnValue_t initialize() override;
private:
std::vector<Max31865ReaderCookie*> rtds;
std::array<uint8_t, 4> cmdBuf = {};
size_t dbLen = 0;
MutexIF* readerMutex;
SpiComIF* comIF;
GpioIF* gpioIF;
MutexIF::TimeoutType csTimeoutType = MutexIF::TimeoutType::BLOCKING;
uint32_t csTimeoutMs = 0;
MutexIF* csLock = nullptr;
bool periodicInitHandling();
ReturnValue_t periodicReadReqHandling();
ReturnValue_t periodicReadHandling();
bool rtdIsActive(uint8_t idx);
ReturnValue_t writeCfgReg(SpiCookie* cookie, uint8_t cfg);
ReturnValue_t writeBiasSel(MAX31865::Bias bias, SpiCookie* cookie, uint8_t baseCfg);
ReturnValue_t readCfgReg(SpiCookie* cookie, uint8_t& cfg);
ReturnValue_t readRtdVal(SpiCookie* cookie, uint16_t& val, bool& faultBitSet);
ReturnValue_t writeLowThreshold(SpiCookie* cookie, uint16_t val);
ReturnValue_t writeHighThreshold(SpiCookie* cookie, uint16_t val);
ReturnValue_t readLowThreshold(SpiCookie* cookie, uint16_t& val);
ReturnValue_t readHighThreshold(SpiCookie* cookie, uint16_t& val);
ReturnValue_t clearFaultStatus(SpiCookie* cookie);
ReturnValue_t readNFromReg(SpiCookie* cookie, uint8_t reg, size_t n, uint8_t** reply);
ReturnValue_t writeNToReg(SpiCookie* cookie, uint8_t reg, size_t n, uint8_t* cmd,
uint8_t** reply);
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 handleSpiError(Max31865ReaderCookie* cookie, ReturnValue_t result, const char* ctx);
};
#endif /* LINUX_DEVICES_MAX31865RTDREADER_H_ */

View File

@ -26,6 +26,11 @@ static const DeviceCommandId_t TC_REPLAY_WRITE_SEQUENCE = 13;
static const DeviceCommandId_t TC_DOWNLINK_PWR_ON = 14;
static const DeviceCommandId_t TC_DOWNLINK_PWR_OFF = 15;
static const DeviceCommandId_t TC_MODE_REPLAY = 16;
static const DeviceCommandId_t TC_CAM_CMD_SEND = 17;
static const DeviceCommandId_t TC_MODE_IDLE = 18;
static const DeviceCommandId_t TM_CAM_CMD_RPT = 19;
static const DeviceCommandId_t SET_UART_TX_TRISTATE = 20;
static const DeviceCommandId_t RELEASE_UART_TX = 21;
// Will reset the sequence count of the OBSW
static const DeviceCommandId_t OBSW_RESET_SEQ_COUNT = 50;
@ -33,6 +38,7 @@ static const DeviceCommandId_t OBSW_RESET_SEQ_COUNT = 50;
static const uint16_t SIZE_ACK_REPORT = 14;
static const uint16_t SIZE_EXE_REPORT = 14;
static const uint16_t SIZE_TM_MEM_READ_REPORT = 18;
static const uint16_t SIZE_TM_CAM_CMD_RPT = 18;
/**
* SpacePacket apids of PLOC telecommands and telemetry.
@ -49,18 +55,23 @@ static const uint16_t TC_FLASHFOPEN = 0x119;
static const uint16_t TC_FLASHFCLOSE = 0x11A;
static const uint16_t TC_FLASHDELETE = 0x11C;
static const uint16_t TC_MODE_REPLAY = 0x11F;
static const uint16_t TC_MODE_IDLE = 0x11E;
static const uint16_t TC_DOWNLINK_PWR_OFF = 0x124;
static const uint16_t TC_CAM_CMD_SEND = 0x12C;
static const uint16_t TM_MEMORY_READ_REPORT = 0x404;
static const uint16_t ACK_SUCCESS = 0x400;
static const uint16_t ACK_FAILURE = 0x401;
static const uint16_t EXE_SUCCESS = 0x402;
static const uint16_t EXE_FAILURE = 0x403;
static const uint16_t TM_CAM_CMD_RPT = 0x407;
} // namespace apid
/** Offset from first byte in space packet to first byte of data field */
static const uint8_t DATA_FIELD_OFFSET = 6;
static const size_t MEM_READ_RPT_LEN_OFFSET = 10;
static const char NULL_TERMINATOR = '\0';
static const uint8_t MIN_SPACE_PACKET_LENGTH = 7;
static const uint8_t SPACE_PACKET_HEADER_SIZE = 6;
/**
* The size of payload data which will be forwarded to the requesting object. e.g. PUS Service
@ -117,11 +128,11 @@ class TcBase : public SpacePacket, public MPSoCReturnValuesIF {
virtual ReturnValue_t createPacket(const uint8_t* commandData, size_t commandDataLen) {
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
result = initPacket(commandData, commandDataLen);
if (result != HasReturnvaluesIF::HasReturnvaluesIF::RETURN_OK) {
if (result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
result = addCrc();
if (result != HasReturnvaluesIF::HasReturnvaluesIF::RETURN_OK) {
if (result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
return result;
@ -567,6 +578,9 @@ class TcReplayWriteSeq : public TcBase {
}
};
/**
* @brief Helps to extract the fields of the flash write command from the PUS packet.
*/
class FlashWritePusCmd : public MPSoCReturnValuesIF {
public:
FlashWritePusCmd(){};
@ -615,6 +629,45 @@ class TcModeReplay : public TcBase {
}
};
/**
* @brief Class to build mode idle command
*/
class TcModeIdle : public TcBase {
public:
TcModeIdle(uint16_t sequenceCount) : TcBase(apid::TC_MODE_IDLE, sequenceCount) {}
ReturnValue_t createPacket() {
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
result = addCrc();
if (result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
this->setPacketDataLength(static_cast<uint16_t>(CRC_SIZE - 1));
return HasReturnvaluesIF::RETURN_OK;
}
};
class TcCamcmdSend : public TcBase {
public:
TcCamcmdSend(uint16_t sequenceCount) : TcBase(apid::TC_CAM_CMD_SEND, sequenceCount) {}
protected:
ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) {
if (commandDataLen > MAX_DATA_LENGTH) {
return INVALID_LENGTH;
}
std::memcpy(this->getPacketData(), commandData, commandDataLen);
*(this->getPacketData() + commandDataLen) = CARRIAGE_RETURN;
uint16_t trueLength = commandDataLen + sizeof(CARRIAGE_RETURN) + CRC_SIZE;
this->setPacketDataLength(trueLength - 1);
return HasReturnvaluesIF::RETURN_OK;
}
private:
static const uint8_t MAX_DATA_LENGTH = 10;
static const uint8_t CARRIAGE_RETURN = 0xD;
};
} // namespace mpsoc
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_PLOCMPSOCDEFINITIONS_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,61 @@
#ifndef SUPV_RETURN_VALUES_IF_H_
#define SUPV_RETURN_VALUES_IF_H_
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
class SupvReturnValuesIF {
public:
static const uint8_t INTERFACE_ID = CLASS_ID::SUPV_RETURN_VALUES_IF;
//! [EXPORT] : [COMMENT] Space Packet received from PLOC supervisor has invalid CRC
static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xA0);
//! [EXPORT] : [COMMENT] Received ACK failure reply from PLOC supervisor
static const ReturnValue_t RECEIVED_ACK_FAILURE = MAKE_RETURN_CODE(0xA1);
//! [EXPORT] : [COMMENT] Received execution failure reply from PLOC supervisor
static const ReturnValue_t RECEIVED_EXE_FAILURE = MAKE_RETURN_CODE(0xA2);
//! [EXPORT] : [COMMENT] Received space packet with invalid APID from PLOC supervisor
static const ReturnValue_t INVALID_APID = MAKE_RETURN_CODE(0xA3);
//! [EXPORT] : [COMMENT] Failed to read current system time
static const ReturnValue_t GET_TIME_FAILURE = MAKE_RETURN_CODE(0xA4);
//! [EXPORT] : [COMMENT] Received command with invalid watchdog parameter. Valid watchdogs are 0
//! for PS, 1 for PL and 2 for INT
static const ReturnValue_t INVALID_WATCHDOG = MAKE_RETURN_CODE(0xA5);
//! [EXPORT] : [COMMENT] Received watchdog timeout config command with invalid timeout. Valid
//! timeouts must be in the range between 1000 and 360000 ms.
static const ReturnValue_t INVALID_WATCHDOG_TIMEOUT = MAKE_RETURN_CODE(0xA6);
//! [EXPORT] : [COMMENT] Received latchup config command with invalid latchup ID
static const ReturnValue_t INVALID_LATCHUP_ID = MAKE_RETURN_CODE(0xA7);
//! [EXPORT] : [COMMENT] Received set adc sweep period command with invalid sweep period. Must be
//! larger than 21.
static const ReturnValue_t SWEEP_PERIOD_TOO_SMALL = MAKE_RETURN_CODE(0xA8);
//! [EXPORT] : [COMMENT] Receive auto EM test command with invalid test param. Valid params are 1
//! and 2.
static const ReturnValue_t INVALID_TEST_PARAM = MAKE_RETURN_CODE(0xA9);
//! [EXPORT] : [COMMENT] Returned when scanning for MRAM dump packets failed.
static const ReturnValue_t MRAM_PACKET_PARSING_FAILURE = MAKE_RETURN_CODE(0xAA);
//! [EXPORT] : [COMMENT] Returned when the start and stop addresses of the MRAM dump or MRAM wipe
//! commands are invalid (e.g. start address bigger than stop address)
static const ReturnValue_t INVALID_MRAM_ADDRESSES = MAKE_RETURN_CODE(0xAB);
//! [EXPORT] : [COMMENT] Expect reception of an MRAM dump packet but received space packet with
//! other apid.
static const ReturnValue_t NO_MRAM_PACKET = MAKE_RETURN_CODE(0xAC);
//! [EXPORT] : [COMMENT] Path to PLOC directory on SD card does not exist
static const ReturnValue_t PATH_DOES_NOT_EXIST = MAKE_RETURN_CODE(0xAD);
//! [EXPORT] : [COMMENT] MRAM dump file does not exists. The file should actually already have
//! been created with the reception of the first dump packet.
static const ReturnValue_t MRAM_FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xAE);
//! [EXPORT] : [COMMENT] Received action command has invalid length
static const ReturnValue_t INVALID_LENGTH = MAKE_RETURN_CODE(0xAF);
//! [EXPORT] : [COMMENT] Filename too long
static const ReturnValue_t FILENAME_TOO_LONG = MAKE_RETURN_CODE(0xB0);
//! [EXPORT] : [COMMENT] Received update status report with invalid packet length field
static const ReturnValue_t UPDATE_STATUS_REPORT_INVALID_LENGTH = MAKE_RETURN_CODE(0xB1);
//! [EXPORT] : [COMMENT] Update status report does not contain expected CRC. There might be a bit
//! flip in the update memory region.
static const ReturnValue_t UPDATE_CRC_FAILURE = MAKE_RETURN_CODE(0xB2);
//! [EXPORT] : [COMMENT] Supervisor helper task ist currently executing a command (wait until
//! helper tas has finished or interrupt by sending the terminate command)
static const ReturnValue_t SUPV_HELPER_EXECUTING = MAKE_RETURN_CODE(0xB3);
};
#endif /* SUPV_RETURN_VALUES_IF_H_ */

View File

@ -1,7 +1,4 @@
target_sources(${OBSW_NAME} PRIVATE
PlocSupervisorHandler.cpp
PlocUpdater.cpp
PlocMemoryDumper.cpp
PlocMPSoCHandler.cpp
PlocMPSoCHelper.cpp
)
target_sources(
${OBSW_NAME}
PRIVATE PlocSupervisorHandler.cpp PlocMemoryDumper.cpp PlocMPSoCHandler.cpp
PlocMPSoCHelper.cpp PlocSupvHelper.cpp)

View File

@ -99,6 +99,20 @@ void PlocMPSoCHandler::performOperationHook() {
ReturnValue_t PlocMPSoCHandler::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
const uint8_t* data, size_t size) {
ReturnValue_t result = RETURN_OK;
switch (actionId) {
case mpsoc::SET_UART_TX_TRISTATE: {
uartIsolatorSwitch.pullLow();
return EXECUTION_FINISHED;
break;
}
case mpsoc::RELEASE_UART_TX: {
uartIsolatorSwitch.pullHigh();
return EXECUTION_FINISHED;
break;
default:
break;
}
}
if (plocMPSoCHelperExecuting) {
return MPSoCReturnValuesIF::MPSOC_HELPER_EXECUTING;
@ -133,6 +147,8 @@ ReturnValue_t PlocMPSoCHandler::executeAction(ActionId_t actionId, MessageQueueI
}
void PlocMPSoCHandler::doStartUp() {
#ifdef XIPHOS_Q7S
#if not OBSW_MPSOC_JTAG_BOOT == 1
switch (powerState) {
case PowerState::OFF:
commandActionHelper.commandAction(supervisorHandler, supv::START_MPSOC);
@ -145,9 +161,20 @@ void PlocMPSoCHandler::doStartUp() {
default:
break;
}
#else
powerState = PowerState::ON;
setMode(_MODE_TO_ON);
uartIsolatorSwitch.pullHigh();
#endif /* not MSPOC_JTAG_BOOT == 1 */
#else
powerState = PowerState::ON;
setMode(_MODE_TO_ON);
#endif /* XIPHOS_Q7S */
}
void PlocMPSoCHandler::doShutDown() {
#ifdef XIPHOS_Q7S
#if not OBSW_MPSOC_JTAG_BOOT == 1
switch (powerState) {
case PowerState::ON:
uartIsolatorSwitch.pullLow();
@ -160,6 +187,12 @@ void PlocMPSoCHandler::doShutDown() {
default:
break;
}
#else
uartIsolatorSwitch.pullLow();
setMode(_MODE_POWER_DOWN);
powerState = PowerState::OFF;
#endif
#endif
}
ReturnValue_t PlocMPSoCHandler::buildNormalDeviceCommand(DeviceCommandId_t* id) {
@ -211,6 +244,14 @@ ReturnValue_t PlocMPSoCHandler::buildCommandFromCommand(DeviceCommandId_t device
result = prepareTcModeReplay();
break;
}
case (mpsoc::TC_MODE_IDLE): {
result = prepareTcModeIdle();
break;
}
case (mpsoc::TC_CAM_CMD_SEND): {
result = prepareTcCamCmdSend(commandData, commandDataLen);
break;
}
default:
sif::debug << "PlocMPSoCHandler::buildCommandFromCommand: Command not implemented"
<< std::endl;
@ -238,16 +279,23 @@ void PlocMPSoCHandler::fillCommandAndReplyMap() {
this->insertInCommandMap(mpsoc::TC_DOWNLINK_PWR_OFF);
this->insertInCommandMap(mpsoc::TC_REPLAY_WRITE_SEQUENCE);
this->insertInCommandMap(mpsoc::TC_MODE_REPLAY);
this->insertInReplyMap(mpsoc::ACK_REPORT, 1, nullptr, mpsoc::SIZE_ACK_REPORT);
this->insertInCommandMap(mpsoc::TC_MODE_IDLE);
this->insertInCommandMap(mpsoc::TC_CAM_CMD_SEND);
this->insertInCommandMap(mpsoc::RELEASE_UART_TX);
this->insertInCommandMap(mpsoc::SET_UART_TX_TRISTATE);
this->insertInReplyMap(mpsoc::ACK_REPORT, 3, nullptr, mpsoc::SIZE_ACK_REPORT);
this->insertInReplyMap(mpsoc::EXE_REPORT, 3, nullptr, mpsoc::SIZE_EXE_REPORT);
this->insertInReplyMap(mpsoc::TM_MEMORY_READ_REPORT, 2, nullptr, mpsoc::SIZE_TM_MEM_READ_REPORT);
this->insertInReplyMap(mpsoc::TM_CAM_CMD_RPT, 2, nullptr, SpacePacket::PACKET_MAX_SIZE);
}
ReturnValue_t PlocMPSoCHandler::scanForReply(const uint8_t* start, size_t remainingSize,
DeviceCommandId_t* foundId, size_t* foundLen) {
ReturnValue_t result = RETURN_OK;
uint16_t apid = (*(start) << 8 | *(start + 1)) & APID_MASK;
SpacePacket spacePacket;
std::memcpy(spacePacket.getWholeData(), start, remainingSize);
uint16_t apid = spacePacket.getAPID();
switch (apid) {
case (mpsoc::apid::ACK_SUCCESS):
@ -262,6 +310,11 @@ ReturnValue_t PlocMPSoCHandler::scanForReply(const uint8_t* start, size_t remain
*foundLen = tmMemReadReport.rememberRequestedSize;
*foundId = mpsoc::TM_MEMORY_READ_REPORT;
break;
case (mpsoc::apid::TM_CAM_CMD_RPT):
*foundLen = spacePacket.getFullSize();
tmCamCmdRpt.rememberSpacePacketSize = *foundLen;
*foundId = mpsoc::TM_CAM_CMD_RPT;
break;
case (mpsoc::apid::EXE_SUCCESS):
*foundLen = mpsoc::SIZE_EXE_REPORT;
*foundId = mpsoc::EXE_REPORT;
@ -276,10 +329,11 @@ ReturnValue_t PlocMPSoCHandler::scanForReply(const uint8_t* start, size_t remain
return MPSoCReturnValuesIF::INVALID_APID;
}
}
sequenceCount++;
uint16_t recvSeqCnt = (*(start + 2) << 8 | *(start + 3)) & PACKET_SEQUENCE_COUNT_MASK;
if (recvSeqCnt != sequenceCount) {
triggerEvent(MPSOC_HANDLER_SEQ_CNT_MISMATCH, sequenceCount, recvSeqCnt);
triggerEvent(MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH, sequenceCount, recvSeqCnt);
sequenceCount = recvSeqCnt;
}
return result;
@ -297,6 +351,10 @@ ReturnValue_t PlocMPSoCHandler::interpretDeviceReply(DeviceCommandId_t id, const
result = handleMemoryReadReport(packet);
break;
}
case (mpsoc::TM_CAM_CMD_RPT): {
result = handleCamCmdRpt(packet);
break;
}
case (mpsoc::EXE_REPORT): {
result = handleExecutionReport(packet);
break;
@ -463,6 +521,37 @@ ReturnValue_t PlocMPSoCHandler::prepareTcModeReplay() {
return RETURN_OK;
}
ReturnValue_t PlocMPSoCHandler::prepareTcModeIdle() {
ReturnValue_t result = RETURN_OK;
sequenceCount++;
mpsoc::TcModeIdle tcModeIdle(sequenceCount);
result = tcModeIdle.createPacket();
if (result != RETURN_OK) {
sequenceCount--;
return result;
}
memcpy(commandBuffer, tcModeIdle.getWholeData(), tcModeIdle.getFullSize());
rawPacket = commandBuffer;
rawPacketLen = tcModeIdle.getFullSize();
nextReplyId = mpsoc::ACK_REPORT;
return RETURN_OK;
}
ReturnValue_t PlocMPSoCHandler::prepareTcCamCmdSend(const uint8_t* commandData,
size_t commandDataLen) {
ReturnValue_t result = RETURN_OK;
sequenceCount++;
mpsoc::TcCamcmdSend tcCamCmdSend(sequenceCount);
result = tcCamCmdSend.createPacket(commandData, commandDataLen);
if (result != RETURN_OK) {
sequenceCount--;
return result;
}
copyToCommandBuffer(&tcCamCmdSend);
nextReplyId = mpsoc::TM_CAM_CMD_RPT;
return RETURN_OK;
}
void PlocMPSoCHandler::copyToCommandBuffer(mpsoc::TcBase* tc) {
if (tc == nullptr) {
sif::debug << "PlocMPSoCHandler::copyToCommandBuffer: Invalid TC" << std::endl;
@ -586,6 +675,28 @@ ReturnValue_t PlocMPSoCHandler::handleMemoryReadReport(const uint8_t* data) {
return result;
}
ReturnValue_t PlocMPSoCHandler::handleCamCmdRpt(const uint8_t* data) {
ReturnValue_t result = RETURN_OK;
SpacePacket packet;
std::memcpy(packet.getWholeData(), data, tmCamCmdRpt.rememberSpacePacketSize);
result = verifyPacket(data, tmCamCmdRpt.rememberSpacePacketSize);
if (result == MPSoCReturnValuesIF::CRC_FAILURE) {
sif::warning << "PlocMPSoCHandler::handleCamCmdRpt: CRC failure" << std::endl;
}
const uint8_t* dataFieldPtr = data + mpsoc::SPACE_PACKET_HEADER_SIZE;
std::string camCmdRptMsg(
reinterpret_cast<const char*>(dataFieldPtr),
tmCamCmdRpt.rememberSpacePacketSize - mpsoc::SPACE_PACKET_HEADER_SIZE - 3);
#if OBSW_DEBUG_PLOC_MPSOC == 1
uint8_t ackValue = *(packet.getPacketData() + packet.getPacketDataLength() - 2);
sif::info << "PlocMPSoCHandler: CamCmdRpt message: " << camCmdRptMsg << std::endl;
sif::info << "PlocMPSoCHandler: CamCmdRpt Ack value: 0x" << std::hex
<< static_cast<unsigned int>(ackValue) << std::endl;
#endif /* OBSW_DEBUG_PLOC_MPSOC == 1 */
handleDeviceTM(packet.getPacketData(), packet.getPacketDataLength() - 1, mpsoc::TM_CAM_CMD_RPT);
return result;
}
ReturnValue_t PlocMPSoCHandler::enableReplyInReplyMap(DeviceCommandMap::iterator command,
uint8_t expectedReplies, bool useAlternateId,
DeviceCommandId_t alternateReplyID) {
@ -602,6 +713,7 @@ ReturnValue_t PlocMPSoCHandler::enableReplyInReplyMap(DeviceCommandMap::iterator
case mpsoc::TC_DOWNLINK_PWR_OFF:
case mpsoc::TC_REPLAY_WRITE_SEQUENCE:
case mpsoc::TC_MODE_REPLAY:
case mpsoc::TC_MODE_IDLE:
enabledReplies = 2;
break;
case mpsoc::TC_MEM_READ: {
@ -611,6 +723,18 @@ ReturnValue_t PlocMPSoCHandler::enableReplyInReplyMap(DeviceCommandMap::iterator
if (result != RETURN_OK) {
sif::debug << "PlocMPSoCHandler::enableReplyInReplyMap: Reply with id "
<< mpsoc::TM_MEMORY_READ_REPORT << " not in replyMap" << std::endl;
return result;
}
break;
}
case mpsoc::TC_CAM_CMD_SEND: {
enabledReplies = 3;
result = DeviceHandlerBase::enableReplyInReplyMap(command, enabledReplies, true,
mpsoc::TM_CAM_CMD_RPT);
if (result != RETURN_OK) {
sif::debug << "PlocMPSoCHandler::enableReplyInReplyMap: Reply with id "
<< mpsoc::TM_CAM_CMD_RPT << " not in replyMap" << std::endl;
return result;
}
break;
}
@ -690,6 +814,11 @@ size_t PlocMPSoCHandler::getNextReplyLength(DeviceCommandId_t commandId) {
replyLen = tmMemReadReport.rememberRequestedSize;
break;
}
case mpsoc::TM_CAM_CMD_RPT:
// Read acknowledgment, camera and execution report in one go because length of camera
// report is not fixed
replyLen = SpacePacket::PACKET_MAX_SIZE;
break;
default: {
replyLen = iter->second.replyLen;
break;
@ -703,6 +832,14 @@ size_t PlocMPSoCHandler::getNextReplyLength(DeviceCommandId_t commandId) {
return replyLen;
}
ReturnValue_t PlocMPSoCHandler::doSendReadHook() {
// Prevent DHB from polling UART during commands executed by the mpsoc helper task
if (plocMPSoCHelperExecuting) {
return RETURN_FAILED;
}
return RETURN_OK;
}
MessageQueueIF* PlocMPSoCHandler::getCommandQueuePtr() { return commandActionHelperQueue; }
void PlocMPSoCHandler::stepSuccessfulReceived(ActionId_t actionId, uint8_t step) { return; }
@ -710,16 +847,19 @@ void PlocMPSoCHandler::stepSuccessfulReceived(ActionId_t actionId, uint8_t step)
void PlocMPSoCHandler::stepFailedReceived(ActionId_t actionId, uint8_t step,
ReturnValue_t returnCode) {
switch (actionId) {
case supv::START_MPSOC:
case supv::START_MPSOC: {
sif::warning << "PlocMPSoCHandler::stepFailedReceived: Failed to start MPSoC" << std::endl;
// This usually happens when the supervisor handler is in off mode
powerState = PowerState::OFF;
setMode(MODE_OFF);
break;
case supv::SHUTDOWN_MPSOC:
}
case supv::SHUTDOWN_MPSOC: {
triggerEvent(MPSOC_SHUTDOWN_FAILED);
sif::warning << "PlocMPSoCHandler::stepFailedReceived: Failed to shutdown MPSoC" << std::endl;
// TODO: Setting state to on or off here?
powerState = PowerState::ON;
powerState = PowerState::OFF;
break;
}
default:
sif::debug << "PlocMPSoCHandler::stepFailedReceived: Received unexpected action reply"
<< std::endl;
@ -783,10 +923,11 @@ void PlocMPSoCHandler::handleDeviceTM(const uint8_t* data, size_t dataSize,
}
void PlocMPSoCHandler::disableAllReplies() {
using namespace mpsoc;
DeviceReplyMap::iterator iter;
/* Disable ack reply */
iter = deviceReplyMap.find(mpsoc::ACK_REPORT);
iter = deviceReplyMap.find(ACK_REPORT);
DeviceReplyInfo* info = &(iter->second);
info->delayCycles = 0;
info->command = deviceCommandMap.end();
@ -795,17 +936,26 @@ void PlocMPSoCHandler::disableAllReplies() {
/* If the command expects a telemetry packet the appropriate tm reply will be disabled here */
switch (commandId) {
case mpsoc::TC_MEM_WRITE:
case TC_MEM_WRITE:
break;
case mpsoc::TC_MEM_READ: {
iter = deviceReplyMap.find(mpsoc::TM_MEMORY_READ_REPORT);
case TC_MEM_READ: {
iter = deviceReplyMap.find(TM_MEMORY_READ_REPORT);
info = &(iter->second);
info->delayCycles = 0;
info->active = false;
info->command = deviceCommandMap.end();
break;
}
case TC_CAM_CMD_SEND: {
iter = deviceReplyMap.find(TM_CAM_CMD_RPT);
info = &(iter->second);
info->delayCycles = 0;
info->active = false;
info->command = deviceCommandMap.end();
break;
}
default: {
sif::debug << "PlocMPSoCHandler::disableAllReplies: Unknown command id" << commandId
sif::debug << "PlocMPSoCHandler::disableAllReplies: Unknown command id: " << commandId
<< std::endl;
break;
}
@ -863,15 +1013,19 @@ void PlocMPSoCHandler::handleActionCommandFailure(ActionId_t actionId) {
}
switch (powerState) {
case PowerState::BOOTING: {
sif::warning << "PlocMPSoCHandler::handleActionCommandFailure: Failed to boot MPSoC"
<< std::endl;
powerState = PowerState::OFF;
sif::info << "PlocMPSoCHandler::handleActionCommandFailure: MPSoC boot command failed"
<< std::endl;
// This is commonly the case when the MPSoC is already operational. Thus the power state is
// set to on here
powerState = PowerState::ON;
break;
}
case PowerState::SHUTDOWN: {
// FDIR will intercept event and switch PLOC power off
triggerEvent(MPSOC_SHUTDOWN_FAILED);
sif::warning << "PlocMPSoCHandler::handleActionCommandFailure: Failed to shutdown MPSoC"
<< std::endl;
powerState = PowerState::ON;
powerState = PowerState::OFF;
break;
}
default:

View File

@ -8,11 +8,13 @@
#include "fsfw/action/CommandsActionsIF.h"
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
#include "fsfw/ipc/QueueFactory.h"
#include "fsfw/tmtcpacket/SpacePacket.h"
#include "fsfw/tmtcservices/SourceSequenceCounter.h"
#include "fsfw_hal/linux/gpio/Gpio.h"
#include "fsfw_hal/linux/uart/UartComIF.h"
#include "linux/devices/devicedefinitions/MPSoCReturnValuesIF.h"
#include "linux/devices/devicedefinitions/PlocMPSoCDefinitions.h"
#include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h"
/**
* @brief This is the device handler for the MPSoC of the payload computer.
@ -75,6 +77,7 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
uint8_t expectedReplies = 1, bool useAlternateId = false,
DeviceCommandId_t alternateReplyID = 0) override;
size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override;
virtual ReturnValue_t doSendReadHook() override;
private:
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_MPSOC_HANDLER;
@ -93,7 +96,7 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
static const Event MPSOC_HANDLER_CRC_FAILURE = MAKE_EVENT(4, severity::LOW);
//! [EXPORT] : [COMMENT] Packet sequence count in received space packet does not match expected
//! count P1: Expected sequence count P2: Received sequence count
static const Event MPSOC_HANDLER_SEQ_CNT_MISMATCH = MAKE_EVENT(5, severity::LOW);
static const Event MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH = MAKE_EVENT(5, severity::LOW);
//! [EXPORT] : [COMMENT] Supervisor fails to shutdown MPSoC. Requires to power off the PLOC and
//! thus also to shutdown the supervisor.
static const Event MPSOC_SHUTDOWN_FAILED = MAKE_EVENT(6, severity::HIGH);
@ -105,7 +108,11 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
MessageQueueIF* eventQueue = nullptr;
MessageQueueIF* commandActionHelperQueue = nullptr;
SourceSequenceCounter sequenceCount;
// Initiate the sequence count with the maximum value. It is incremented before
// a packet is sent, so the first value will be 0 accordingly using
// the wrap around of the counter.
SourceSequenceCounter sequenceCount =
SourceSequenceCounter(SpacePacketBase::LIMIT_SEQUENCE_COUNT - 1);
uint8_t commandBuffer[mpsoc::MAX_COMMAND_SIZE];
@ -126,14 +133,26 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
// Used to block incoming commands when MPSoC helper class is currently executing a command
bool plocMPSoCHelperExecuting = false;
class TmMemReadReport {
public:
struct TmMemReadReport {
static const uint8_t FIX_SIZE = 14;
size_t rememberRequestedSize = 0;
};
TmMemReadReport tmMemReadReport;
struct TmCamCmdRpt {
size_t rememberSpacePacketSize = 0;
};
TmCamCmdRpt tmCamCmdRpt;
struct TelemetryBuffer {
uint16_t length = 0;
uint8_t buffer[SpacePacket::PACKET_MAX_SIZE];
};
TelemetryBuffer tmBuffer;
enum class PowerState { OFF, BOOTING, SHUTDOWN, ON };
PowerState powerState = PowerState::OFF;
@ -151,7 +170,8 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
ReturnValue_t prepareTcDownlinkPwrOn(const uint8_t* commandData, size_t commandDataLen);
ReturnValue_t prepareTcDownlinkPwrOff();
ReturnValue_t prepareTcReplayWriteSequence(const uint8_t* commandData, size_t commandDataLen);
ReturnValue_t prepareTcCamCmdSend(const uint8_t* commandData, size_t commandDataLen);
ReturnValue_t prepareTcModeIdle();
/**
* @brief Copies space packet into command buffer
*/
@ -194,6 +214,8 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
*/
ReturnValue_t handleMemoryReadReport(const uint8_t* data);
ReturnValue_t handleCamCmdRpt(const uint8_t* data);
/**
* @brief Depending on the current active command, this function sets the reply id of the
* next reply after a successful acknowledgment report has been received. This is

View File

@ -204,7 +204,7 @@ ReturnValue_t PlocMPSoCHelper::sendCommand(mpsoc::TcBase& tc) {
result = uartComIF->sendMessage(comCookie, tc.getWholeData(), tc.getFullSize());
if (result != RETURN_OK) {
sif::warning << "PlocMPSoCHelper::sendCommand: Failed to send command" << std::endl;
triggerEvent(SENDING_COMMAND_FAILED, result, static_cast<uint32_t>(internalState));
triggerEvent(MPSOC_SENDING_COMMAND_FAILED, result, static_cast<uint32_t>(internalState));
return result;
}
return result;
@ -227,11 +227,11 @@ ReturnValue_t PlocMPSoCHelper::handleAck() {
void PlocMPSoCHelper::handleAckApidFailure(uint16_t apid) {
if (apid == mpsoc::apid::ACK_FAILURE) {
triggerEvent(ACK_FAILURE_REPORT, static_cast<uint32_t>(internalState));
triggerEvent(MPSOC_ACK_FAILURE_REPORT, static_cast<uint32_t>(internalState));
sif::warning << "PlocMPSoCHelper::handleAckApidFailure: Received acknowledgement failure "
<< "report" << std::endl;
} else {
triggerEvent(ACK_INVALID_APID, apid, static_cast<uint32_t>(internalState));
triggerEvent(MPSOC_ACK_INVALID_APID, apid, static_cast<uint32_t>(internalState));
sif::warning << "PlocMPSoCHelper::handleAckApidFailure: Expected acknowledgement report "
<< "but received space packet with apid " << std::hex << apid << std::endl;
}
@ -254,11 +254,11 @@ ReturnValue_t PlocMPSoCHelper::handleExe() {
void PlocMPSoCHelper::handleExeApidFailure(uint16_t apid) {
if (apid == mpsoc::apid::EXE_FAILURE) {
triggerEvent(EXE_FAILURE_REPORT, static_cast<uint32_t>(internalState));
triggerEvent(MPSOC_EXE_FAILURE_REPORT, static_cast<uint32_t>(internalState));
sif::warning << "PlocMPSoCHelper::handleExeApidFailure: Received execution failure "
<< "report" << std::endl;
} else {
triggerEvent(EXE_INVALID_APID, apid, static_cast<uint32_t>(internalState));
triggerEvent(MPSOC_EXE_INVALID_APID, apid, static_cast<uint32_t>(internalState));
sif::warning << "PlocMPSoCHelper::handleExeApidFailure: Expected execution report "
<< "but received space packet with apid " << std::hex << apid << std::endl;
}
@ -281,7 +281,7 @@ ReturnValue_t PlocMPSoCHelper::handleTmReception(mpsoc::TmPacket* tmPacket, size
}
if (remainingBytes != 0) {
sif::warning << "PlocMPSoCHelper::handleTmReception: Failed to receive reply" << std::endl;
triggerEvent(MISSING_EXE, remainingBytes, static_cast<uint32_t>(internalState));
triggerEvent(MPSOC_MISSING_EXE, remainingBytes, static_cast<uint32_t>(internalState));
return RETURN_FAILED;
}
result = tmPacket->checkCrc();

View File

@ -29,10 +29,10 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF, public H
//! [EXPORT] : [COMMENT] Flash write successful
static const Event MPSOC_FLASH_WRITE_SUCCESSFUL = MAKE_EVENT(1, severity::LOW);
//! [EXPORT] : [COMMENT] Communication interface returned failure when trying to send the command
//! ot the PLOC
//! to the MPSoC
//! P1: Return value returned by the communication interface sendMessage function
//! P2: Internal state of MPSoC helper
static const Event SENDING_COMMAND_FAILED = MAKE_EVENT(2, severity::LOW);
static const Event MPSOC_SENDING_COMMAND_FAILED = MAKE_EVENT(2, severity::LOW);
//! [EXPORT] : [COMMENT] Request receive message of communication interface failed
//! P1: Return value returned by the communication interface requestReceiveMessage function
//! P2: Internal state of MPSoC helper
@ -41,28 +41,28 @@ class PlocMPSoCHelper : public SystemObject, public ExecutableObjectIF, public H
//! P1: Return value returned by the communication interface readingReceivedMessage function
//! P2: Internal state of MPSoC helper
static const Event MPSOC_HELPER_READING_REPLY_FAILED = MAKE_EVENT(4, severity::LOW);
//! [EXPORT] : [COMMENT] Did not receive acknowledgement report
//! [EXPORT] : [COMMENT] Did not receive acknowledgment report
//! P1: Number of bytes missing
//! P2: Internal state of MPSoC helper
static const Event MISSING_ACK = MAKE_EVENT(5, severity::LOW);
static const Event MPSOC_MISSING_ACK = MAKE_EVENT(5, severity::LOW);
//! [EXPORT] : [COMMENT] Did not receive execution report
//! P1: Number of bytes missing
//! P2: Internal state of MPSoC helper
static const Event MISSING_EXE = MAKE_EVENT(6, severity::LOW);
//! [EXPORT] : [COMMENT] Received acknowledgement failure report
static const Event MPSOC_MISSING_EXE = MAKE_EVENT(6, severity::LOW);
//! [EXPORT] : [COMMENT] Received acknowledgment failure report
//! P1: Internal state of MPSoC
static const Event ACK_FAILURE_REPORT = MAKE_EVENT(7, severity::LOW);
static const Event MPSOC_ACK_FAILURE_REPORT = MAKE_EVENT(7, severity::LOW);
//! [EXPORT] : [COMMENT] Received execution failure report
//! P1: Internal state of MPSoC
static const Event EXE_FAILURE_REPORT = MAKE_EVENT(8, severity::LOW);
//! [EXPORT] : [COMMENT] Expected acknowledgement report but received space packet with other apid
static const Event MPSOC_EXE_FAILURE_REPORT = MAKE_EVENT(8, severity::LOW);
//! [EXPORT] : [COMMENT] Expected acknowledgment report but received space packet with other apid
//! P1: Apid of received space packet
//! P2: Internal state of MPSoC
static const Event ACK_INVALID_APID = MAKE_EVENT(9, severity::LOW);
static const Event MPSOC_ACK_INVALID_APID = MAKE_EVENT(9, severity::LOW);
//! [EXPORT] : [COMMENT] Expected execution report but received space packet with other apid
//! P1: Apid of received space packet
//! P2: Internal state of MPSoC
static const Event EXE_INVALID_APID = MAKE_EVENT(10, severity::LOW);
static const Event MPSOC_EXE_INVALID_APID = MAKE_EVENT(10, severity::LOW);
//! [EXPORT] : [COMMENT] Received sequence count does not match expected sequence count
//! P1: Expected sequence count
//! P2: Received sequence count

View File

@ -121,7 +121,10 @@ void PlocMemoryDumper::doStateMachine() {
void PlocMemoryDumper::stepSuccessfulReceived(ActionId_t actionId, uint8_t step) {}
void PlocMemoryDumper::stepFailedReceived(ActionId_t actionId, uint8_t step,
ReturnValue_t returnCode) {}
ReturnValue_t returnCode) {
triggerEvent(MRAM_DUMP_FAILED);
state = State::IDLE;
}
void PlocMemoryDumper::dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) {}
@ -149,10 +152,9 @@ void PlocMemoryDumper::completionFailedReceived(ActionId_t actionId, ReturnValue
case (supv::FIRST_MRAM_DUMP):
case (supv::CONSECUTIVE_MRAM_DUMP):
triggerEvent(MRAM_DUMP_FAILED, mram.lastStartAddress);
pendingCommand = NONE;
break;
default:
sif::debug << "PlocMemoryDumper::completionFailedReceived: Invalid pending command "
<< std::endl;
break;
}
state = State::IDLE;
@ -168,12 +170,12 @@ void PlocMemoryDumper::commandNextMramDump(ActionId_t dumpCommand) {
tempStartAddress = mram.startAddress;
tempEndAddress = mram.startAddress + MAX_MRAM_DUMP_SIZE;
mram.startAddress += MAX_MRAM_DUMP_SIZE;
mram.lastStartAddress = tempStartAddress;
} else {
tempStartAddress = mram.startAddress;
tempEndAddress = mram.endAddress;
mram.startAddress = mram.endAddress;
}
mram.lastStartAddress = tempStartAddress;
MemoryParams params(tempStartAddress, tempEndAddress);

File diff suppressed because it is too large Load Diff

View File

@ -2,19 +2,22 @@
#define MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_
#include "OBSWConfig.h"
#include "PlocSupvHelper.h"
#include "bsp_q7s/memory/SdCardManager.h"
#include "devices/powerSwitcherList.h"
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
#include "fsfw/timemanager/Countdown.h"
#include "fsfw_hal/linux/gpio/Gpio.h"
#include "fsfw_hal/linux/gpio/LinuxLibgpioIF.h"
#include "fsfw_hal/linux/uart/UartComIF.h"
#include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h"
#include "linux/devices/devicedefinitions/SupvReturnValuesIF.h"
/**
* @brief This is the device handler for the supervisor of the PLOC which is programmed by
* Thales.
*
* @details The PLOC uses the space packet protocol for communication. To each command the PLOC
* @details The PLOC uses the space packet protocol for communication. On each command the PLOC
* answers with at least one acknowledgment and one execution report.
* Flight manual:
* https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/PLOC_Commands
@ -25,10 +28,14 @@
class PlocSupervisorHandler : public DeviceHandlerBase {
public:
PlocSupervisorHandler(object_id_t objectId, object_id_t uartComIFid, CookieIF* comCookie,
Gpio uartIsolatorSwitch, power::Switch_t powerSwitch);
Gpio uartIsolatorSwitch, power::Switch_t powerSwitch,
PlocSupvHelper* supvHelper);
virtual ~PlocSupervisorHandler();
virtual ReturnValue_t initialize() override;
void performOperationHook() override;
ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
const uint8_t* data, size_t size) override;
protected:
void doStartUp() override;
@ -49,48 +56,10 @@ class PlocSupervisorHandler : public DeviceHandlerBase {
uint8_t expectedReplies = 1, bool useAlternateId = false,
DeviceCommandId_t alternateReplyID = 0) override;
size_t getNextReplyLength(DeviceCommandId_t deviceCommand) override;
ReturnValue_t doSendReadHook() override;
void doOffActivity() override;
private:
static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_SUPERVISOR_HANDLER;
//! [EXPORT] : [COMMENT] Space Packet received from PLOC supervisor has invalid CRC
static const ReturnValue_t CRC_FAILURE = MAKE_RETURN_CODE(0xA0);
//! [EXPORT] : [COMMENT] Received ACK failure reply from PLOC supervisor
static const ReturnValue_t RECEIVED_ACK_FAILURE = MAKE_RETURN_CODE(0xA1);
//! [EXPORT] : [COMMENT] Received execution failure reply from PLOC supervisor
static const ReturnValue_t RECEIVED_EXE_FAILURE = MAKE_RETURN_CODE(0xA2);
//! [EXPORT] : [COMMENT] Received space packet with invalid APID from PLOC supervisor
static const ReturnValue_t INVALID_APID = MAKE_RETURN_CODE(0xA3);
//! [EXPORT] : [COMMENT] Failed to read current system time
static const ReturnValue_t GET_TIME_FAILURE = MAKE_RETURN_CODE(0xA4);
//! [EXPORT] : [COMMENT] Received command with invalid watchdog parameter. Valid watchdogs are 0
//! for PS, 1 for PL and 2 for INT
static const ReturnValue_t INVALID_WATCHDOG = MAKE_RETURN_CODE(0xA5);
//! [EXPORT] : [COMMENT] Received watchdog timeout config command with invalid timeout. Valid
//! timeouts must be in the range between 1000 and 360000 ms.
static const ReturnValue_t INVALID_WATCHDOG_TIMEOUT = MAKE_RETURN_CODE(0xA6);
//! [EXPORT] : [COMMENT] Received latchup config command with invalid latchup ID
static const ReturnValue_t INVALID_LATCHUP_ID = MAKE_RETURN_CODE(0xA7);
//! [EXPORT] : [COMMENT] Received set adc sweep period command with invalid sweep period. Must be
//! larger than 21.
static const ReturnValue_t SWEEP_PERIOD_TOO_SMALL = MAKE_RETURN_CODE(0xA8);
//! [EXPORT] : [COMMENT] Receive auto EM test command with invalid test param. Valid params are 1
//! and 2.
static const ReturnValue_t INVALID_TEST_PARAM = MAKE_RETURN_CODE(0xA9);
//! [EXPORT] : [COMMENT] Returned when scanning for MRAM dump packets failed.
static const ReturnValue_t MRAM_PACKET_PARSING_FAILURE = MAKE_RETURN_CODE(0xAA);
//! [EXPORT] : [COMMENT] Returned when the start and stop addresses of the MRAM dump or MRAM wipe
//! commands are invalid (e.g. start address bigger than stop address)
static const ReturnValue_t INVALID_MRAM_ADDRESSES = MAKE_RETURN_CODE(0xAB);
//! [EXPORT] : [COMMENT] Expect reception of an MRAM dump packet but received space packet with
//! other apid.
static const ReturnValue_t NO_MRAM_PACKET = MAKE_RETURN_CODE(0xAC);
//! [EXPORT] : [COMMENT] Path to PLOC directory on SD card does not exist
static const ReturnValue_t PATH_DOES_NOT_EXIST = MAKE_RETURN_CODE(0xAD);
//! [EXPORT] : [COMMENT] MRAM dump file does not exists. The file should actually already have
//! been created with the reception of the first dump packet.
static const ReturnValue_t MRAM_FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xAE);
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_SUPERVISOR_HANDLER;
//! [EXPORT] : [COMMENT] PLOC supervisor crc failure in telemetry packet
@ -98,12 +67,35 @@ class PlocSupervisorHandler : public DeviceHandlerBase {
//! [EXPORT] : [COMMENT] PLOC supervisor received acknowledgment failure report
static const Event SUPV_ACK_FAILURE = MAKE_EVENT(2, severity::LOW);
//! [EXPORT] : [COMMENT] PLOC received execution failure report
//! P1: ID of command for which the execution failed
//! P2: Status code sent by the supervisor handler
static const Event SUPV_EXE_FAILURE = MAKE_EVENT(3, severity::LOW);
//! [EXPORT] : [COMMENT] PLOC supervisor reply has invalid crc
static const Event SUPV_CRC_FAILURE_EVENT = MAKE_EVENT(4, severity::LOW);
//! [EXPORT] : [COMMENT] Supervisor helper currently executing a command
static const Event SUPV_HELPER_EXECUTING = MAKE_EVENT(5, severity::LOW);
//! [EXPORT] : [COMMENT] Failed to build the command to shutdown the MPSoC
static const Event SUPV_MPSOC_SHUWDOWN_BUILD_FAILED = MAKE_EVENT(5, severity::LOW);
static const uint16_t APID_MASK = 0x7FF;
static const uint16_t PACKET_SEQUENCE_COUNT_MASK = 0x3FFF;
static const uint8_t EXE_STATUS_OFFSET = 10;
static const uint8_t SIZE_NULL_TERMINATOR = 1;
// 5 s
static const uint32_t EXECUTION_DEFAULT_TIMEOUT = 5000;
// 70 S
static const uint32_t ACKNOWLEDGE_DEFAULT_TIMEOUT = 70000;
// 60 s
static const uint32_t MRAM_DUMP_EXECUTION_TIMEOUT = 60000;
// 70 s
static const uint32_t COPY_ADC_TO_MRAM_TIMEOUT = 70000;
// 60 s
static const uint32_t MRAM_DUMP_TIMEOUT = 60000;
// 2 s
static const uint32_t BOOT_TIMEOUT = 2000;
enum class StartupState : uint8_t { OFF, BOOTING, SET_TIME, SET_TIME_EXECUTING, ON };
StartupState startupState = StartupState::OFF;
uint8_t commandBuffer[supv::MAX_COMMAND_SIZE];
@ -121,9 +113,14 @@ class PlocSupervisorHandler : public DeviceHandlerBase {
supv::HkSet hkset;
supv::BootStatusReport bootStatusReport;
supv::LatchupStatusReport latchupStatusReport;
supv::LoggingReport loggingReport;
supv::AdcReport adcReport;
const power::Switch_t powerSwitch = power::NO_SWITCH;
PlocSupvHelper* supvHelper = nullptr;
MessageQueueIF* eventQueue = nullptr;
/** Number of expected replies following the MRAM dump command */
uint32_t expectedMramDumpPackets = 0;
uint32_t receivedMramDumpPackets = 0;
@ -135,16 +132,32 @@ class PlocSupervisorHandler : public DeviceHandlerBase {
/** This buffer is used to concatenate space packets received in two different read steps */
uint8_t spacePacketBuffer[supv::MAX_PACKET_SIZE];
#ifdef TE0720_1CFA
#ifndef TE0720_1CFA
SdCardManager* sdcMan = nullptr;
#endif /* BOARD_TE0720 == 0 */
/** Path to PLOC specific files on SD card */
std::string plocFilePath = "ploc";
// Path to supervisor specific files on SD card
std::string supervisorFilePath = "ploc/supervisor";
std::string activeMramFile;
/** Setting this variable to true will enable direct downlink of MRAM packets */
bool downlinkMramDump = false;
// Supervisor helper class currently executing a command
bool plocSupvHelperExecuting = false;
Countdown executionReportTimeout = Countdown(EXECUTION_DEFAULT_TIMEOUT, false);
Countdown acknowledgementReportTimeout = Countdown(ACKNOWLEDGE_DEFAULT_TIMEOUT, false);
// Vorago nees some time to boot properly
Countdown bootTimeout = Countdown(BOOT_TIMEOUT);
Countdown mramDumpTimeout = Countdown(MRAM_DUMP_TIMEOUT);
/**
* @brief Adjusts the timeout of the execution report dependent on command
*/
void setExecutionTimeout(DeviceCommandId_t command);
/**
* @brief Handles event messages received from the supervisor helper
*/
void handleEvent(EventMessage* eventMessage);
ReturnValue_t getSwitches(const uint8_t** switches, uint8_t* numberOfSwitches);
@ -193,6 +206,8 @@ class PlocSupervisorHandler : public DeviceHandlerBase {
ReturnValue_t handleBootStatusReport(const uint8_t* data);
ReturnValue_t handleLatchupStatusReport(const uint8_t* data);
ReturnValue_t handleLoggingReport(const uint8_t* data);
ReturnValue_t handleAdcReport(const uint8_t* data);
/**
* @brief Depending on the current active command, this function sets the reply id of the
@ -253,22 +268,17 @@ class PlocSupervisorHandler : public DeviceHandlerBase {
ReturnValue_t prepareLatchupConfigCmd(const uint8_t* commandData,
DeviceCommandId_t deviceCommand);
ReturnValue_t prepareAutoCalibrateAlertCmd(const uint8_t* commandData);
ReturnValue_t prepareSetAlertLimitCmd(const uint8_t* commandData);
ReturnValue_t prepareSetAlertIrqFilterCmd(const uint8_t* commandData);
ReturnValue_t prepareSetAdcSweetPeriodCmd(const uint8_t* commandData);
void prepareSetAdcEnabledChannelsCmd(const uint8_t* commandData);
void prepareSetAdcWindowAndStrideCmd(const uint8_t* commandData);
void prepareSetAdcThresholdCmd(const uint8_t* commandData);
void prepareEnableNvmsCmd(const uint8_t* commandData);
void prepareSelectNvmCmd(const uint8_t* commandData);
ReturnValue_t prepareRunAutoEmTest(const uint8_t* commandData);
ReturnValue_t prepareWipeMramCmd(const uint8_t* commandData);
ReturnValue_t prepareDumpMramCmd(const uint8_t* commandData);
void preparePrintCpuStatsCmd(const uint8_t* commandData);
void prepareSetDbgVerbosityCmd(const uint8_t* commandData);
void prepareSetGpioCmd(const uint8_t* commandData);
void prepareReadGpioCmd(const uint8_t* commandData);
ReturnValue_t prepareLoggingRequest(const uint8_t* commandData, size_t commandDataLen);
ReturnValue_t prepareEnableNvmsCommand(const uint8_t* commandData);
/**
* @brief Copies the content of a space packet to the command buffer.
@ -282,6 +292,8 @@ class PlocSupervisorHandler : public DeviceHandlerBase {
*/
void disableAllReplies();
void disableReply(DeviceCommandId_t replyId);
/**
* @brief This function sends a failure report if the active action was commanded by an other
* object.
@ -348,6 +360,15 @@ class PlocSupervisorHandler : public DeviceHandlerBase {
ReturnValue_t createMramDumpFile();
ReturnValue_t getTimeStampString(std::string& timeStamp);
void prepareSetShutdownTimeoutCmd(const uint8_t* commandData);
ReturnValue_t extractUpdateCommand(const uint8_t* commandData, size_t size, std::string* file,
uint8_t* memoryId, uint32_t* startAddress);
ReturnValue_t eventSubscription();
void handleExecutionSuccessReport(const uint8_t* data);
void handleExecutionFailureReport(uint16_t statusCode);
};
#endif /* MISSION_DEVICES_PLOCSUPERVISORHANDLER_H_ */

View File

@ -0,0 +1,562 @@
#include "PlocSupvHelper.h"
#include <filesystem>
#include <fstream>
#include "OBSWConfig.h"
#ifdef XIPHOS_Q7S
#include "bsp_q7s/memory/FilesystemHelper.h"
#include "bsp_q7s/memory/SdCardManager.h"
#endif
#include "fsfw/globalfunctions/CRC.h"
#include "fsfw/tasks/TaskFactory.h"
#include "fsfw/timemanager/Countdown.h"
#include "mission/utility/Filenaming.h"
#include "mission/utility/ProgressPrinter.h"
#include "mission/utility/Timestamp.h"
PlocSupvHelper::PlocSupvHelper(object_id_t objectId) : SystemObject(objectId) {}
PlocSupvHelper::~PlocSupvHelper() {}
ReturnValue_t PlocSupvHelper::initialize() {
#ifdef XIPHOS_Q7S
sdcMan = SdCardManager::instance();
if (sdcMan == nullptr) {
sif::warning << "PlocSupvHelper::initialize: Invalid SD Card Manager" << std::endl;
return RETURN_FAILED;
}
#endif
return RETURN_OK;
}
ReturnValue_t PlocSupvHelper::performOperation(uint8_t operationCode) {
ReturnValue_t result = RETURN_OK;
semaphore.acquire();
while (true) {
switch (internalState) {
case InternalState::IDLE: {
semaphore.acquire();
break;
}
case InternalState::UPDATE: {
result = performUpdate();
if (result == RETURN_OK) {
triggerEvent(SUPV_UPDATE_SUCCESSFUL, result);
} else if (result == PROCESS_TERMINATED) {
// Event already triggered
} else {
triggerEvent(SUPV_UPDATE_FAILED, result);
}
internalState = InternalState::IDLE;
break;
}
case InternalState::CONTINUE_UPDATE: {
result = continueUpdate();
if (result == RETURN_OK) {
triggerEvent(SUPV_CONTINUE_UPDATE_SUCCESSFUL, result);
} else if (result == PROCESS_TERMINATED) {
// Event already triggered
} else {
triggerEvent(SUPV_CONTINUE_UPDATE_FAILED, result);
}
internalState = InternalState::IDLE;
break;
}
case InternalState::REQUEST_EVENT_BUFFER: {
result = performEventBufferRequest();
if (result == RETURN_OK) {
triggerEvent(SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL, result);
} else if (result == PROCESS_TERMINATED) {
// Event already triggered
break;
} else {
triggerEvent(SUPV_EVENT_BUFFER_REQUEST_FAILED, result);
}
internalState = InternalState::IDLE;
break;
}
default:
sif::debug << "PlocSupvHelper::performOperation: Invalid state" << std::endl;
break;
}
}
}
ReturnValue_t PlocSupvHelper::setComIF(UartComIF* uartComIF_) {
if (uartComIF_ == nullptr) {
sif::warning << "PlocSupvHelper::initialize: Provided invalid uart com if" << std::endl;
return RETURN_FAILED;
}
uartComIF = uartComIF_;
return RETURN_OK;
}
void PlocSupvHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; }
ReturnValue_t PlocSupvHelper::startUpdate(std::string file, uint8_t memoryId,
uint32_t startAddress) {
ReturnValue_t result = RETURN_OK;
#ifdef XIPHOS_Q7S
result = FilesystemHelper::checkPath(file);
if (result != RETURN_OK) {
sif::warning << "PlocSupvHelper::startUpdate: File " << file << " does not exist" << std::endl;
return result;
}
result = FilesystemHelper::fileExists(file);
if (result != RETURN_OK) {
sif::warning << "PlocSupvHelper::startUpdate: The file " << file << " does not exist"
<< std::endl;
return result;
}
#endif
#ifdef TE0720_1CFA
if (not std::filesystem::exists(file)) {
sif::warning << "PlocSupvHelper::startUpdate: The file " << file << " does not exist"
<< std::endl;
return RETURN_FAILED;
}
#endif
update.file = file;
update.length = getFileSize(update.file);
update.memoryId = memoryId;
update.startAddress = startAddress;
update.remainingSize = update.length;
update.bytesWritten = 0;
update.packetNum = 1;
update.sequenceCount = 1;
internalState = InternalState::UPDATE;
uartComIF->flushUartTxAndRxBuf(comCookie);
semaphore.release();
return result;
}
void PlocSupvHelper::initiateUpdateContinuation() {
internalState = InternalState::CONTINUE_UPDATE;
semaphore.release();
}
ReturnValue_t PlocSupvHelper::startEventbBufferRequest(std::string path) {
#ifdef XIPHOS_Q7S
ReturnValue_t result = FilesystemHelper::checkPath(path);
if (result != RETURN_OK) {
return result;
}
#endif
if (not std::filesystem::exists(path)) {
return PATH_NOT_EXISTS;
}
eventBufferReq.path = path;
internalState = InternalState::REQUEST_EVENT_BUFFER;
uartComIF->flushUartTxAndRxBuf(comCookie);
semaphore.release();
return RETURN_OK;
}
void PlocSupvHelper::stopProcess() { terminate = true; }
ReturnValue_t PlocSupvHelper::performUpdate() {
ReturnValue_t result = RETURN_OK;
result = calcImageCrc();
if (result != RETURN_OK) {
return result;
}
result = selectMemory();
if (result != RETURN_OK) {
return result;
}
result = prepareUpdate();
if (result != RETURN_OK) {
return result;
}
result = eraseMemory();
if (result != RETURN_OK) {
return result;
}
result = writeUpdatePackets();
if (result != RETURN_OK) {
return result;
}
result = handleCheckMemoryCommand();
if (result != RETURN_OK) {
return result;
}
return result;
}
ReturnValue_t PlocSupvHelper::continueUpdate() {
ReturnValue_t result = prepareUpdate();
if (result != RETURN_OK) {
return result;
}
result = writeUpdatePackets();
if (result != RETURN_OK) {
return result;
}
result = handleCheckMemoryCommand();
if (result != RETURN_OK) {
return result;
}
return result;
}
ReturnValue_t PlocSupvHelper::writeUpdatePackets() {
ReturnValue_t result = RETURN_OK;
#if OBSW_DEBUG_PLOC_SUPERVISOR == 1
ProgressPrinter progressPrinter("Supervisor update", update.length,
ProgressPrinter::HALF_PERCENT);
#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */
uint8_t tempData[supv::WriteMemory::CHUNK_MAX];
std::ifstream file(update.file, std::ifstream::binary);
uint16_t dataLength = 0;
supv::SequenceFlags seqFlags;
while (update.remainingSize > 0) {
if (terminate) {
terminate = false;
triggerEvent(TERMINATED_UPDATE_PROCEDURE);
return PROCESS_TERMINATED;
}
if (update.remainingSize > supv::WriteMemory::CHUNK_MAX) {
dataLength = supv::WriteMemory::CHUNK_MAX;
} else {
dataLength = static_cast<uint16_t>(update.remainingSize);
}
if (file.is_open()) {
file.seekg(update.bytesWritten, file.beg);
file.read(reinterpret_cast<char*>(tempData), dataLength);
if (!file) {
sif::warning << "PlocSupvHelper::performUpdate: Read only " << file.gcount() << " of "
<< dataLength << " bytes" << std::endl;
sif::info << "PlocSupvHelper::performUpdate: Failed when trying to read byte "
<< update.bytesWritten << std::endl;
}
} else {
return FILE_CLOSED_ACCIDENTALLY;
}
if (update.bytesWritten == 0) {
seqFlags = supv::SequenceFlags::FIRST_PKT;
} else if (update.remainingSize == 0) {
seqFlags = supv::SequenceFlags::LAST_PKT;
} else {
seqFlags = supv::SequenceFlags::CONTINUED_PKT;
}
supv::WriteMemory packet(seqFlags, update.sequenceCount++, update.memoryId,
update.startAddress + update.bytesWritten, dataLength, tempData);
result = handlePacketTransmission(packet);
if (result != RETURN_OK) {
update.sequenceCount--;
triggerEvent(WRITE_MEMORY_FAILED, update.packetNum);
return result;
}
update.remainingSize -= dataLength;
update.packetNum += 1;
update.bytesWritten += dataLength;
#if OBSW_DEBUG_PLOC_SUPERVISOR == 1
progressPrinter.print(update.bytesWritten);
#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */
}
return result;
}
ReturnValue_t PlocSupvHelper::performEventBufferRequest() {
using namespace supv;
ReturnValue_t result = RETURN_OK;
RequestLoggingData packet(RequestLoggingData::Sa::REQUEST_EVENT_BUFFERS);
result = sendCommand(packet);
if (result != RETURN_OK) {
return result;
}
result = handleAck();
if (result != RETURN_OK) {
return result;
}
result = handleEventBufferReception();
if (result != RETURN_OK) {
return result;
}
result = handleExe();
if (result != RETURN_OK) {
return result;
}
return result;
}
ReturnValue_t PlocSupvHelper::selectMemory() {
ReturnValue_t result = RETURN_OK;
supv::MPSoCBootSelect packet(update.memoryId);
result = handlePacketTransmission(packet);
if (result != RETURN_OK) {
return result;
}
return RETURN_OK;
}
ReturnValue_t PlocSupvHelper::prepareUpdate() {
ReturnValue_t result = RETURN_OK;
supv::ApidOnlyPacket packet(supv::APID_PREPARE_UPDATE);
result = handlePacketTransmission(packet, PREPARE_UPDATE_EXECUTION_REPORT);
if (result != RETURN_OK) {
return result;
}
return RETURN_OK;
}
ReturnValue_t PlocSupvHelper::eraseMemory() {
ReturnValue_t result = RETURN_OK;
supv::EraseMemory eraseMemory(update.memoryId, update.startAddress, update.length);
result = handlePacketTransmission(eraseMemory, supv::recv_timeout::ERASE_MEMORY);
if (result != RETURN_OK) {
return result;
}
return RETURN_OK;
}
ReturnValue_t PlocSupvHelper::handlePacketTransmission(SpacePacket& packet,
uint32_t timeoutExecutionReport) {
ReturnValue_t result = RETURN_OK;
result = sendCommand(packet);
if (result != RETURN_OK) {
return result;
}
result = handleAck();
if (result != RETURN_OK) {
return result;
}
result = handleExe(timeoutExecutionReport);
if (result != RETURN_OK) {
return result;
}
return RETURN_OK;
}
ReturnValue_t PlocSupvHelper::sendCommand(SpacePacket& packet) {
ReturnValue_t result = RETURN_OK;
rememberApid = packet.getAPID();
result = uartComIF->sendMessage(comCookie, packet.getWholeData(), packet.getFullSize());
if (result != RETURN_OK) {
sif::warning << "PlocSupvHelper::sendCommand: Failed to send command" << std::endl;
triggerEvent(SUPV_SENDING_COMMAND_FAILED, result, static_cast<uint32_t>(internalState));
return result;
}
return result;
}
ReturnValue_t PlocSupvHelper::handleAck() {
ReturnValue_t result = RETURN_OK;
supv::AcknowledgmentReport ackReport;
result = handleTmReception(&ackReport, supv::SIZE_ACK_REPORT);
if (result != RETURN_OK) {
triggerEvent(ACK_RECEPTION_FAILURE, result, static_cast<uint32_t>(rememberApid));
sif::warning << "PlocSupvHelper::handleAck: Error in reception of acknowledgment report"
<< std::endl;
return result;
}
result = ackReport.checkApid();
if (result != RETURN_OK) {
if (result == SupvReturnValuesIF::RECEIVED_ACK_FAILURE) {
triggerEvent(SUPV_ACK_FAILURE_REPORT, static_cast<uint32_t>(ackReport.getRefApid()));
} else if (result == SupvReturnValuesIF::INVALID_APID) {
triggerEvent(SUPV_ACK_INVALID_APID, static_cast<uint32_t>(rememberApid));
}
return result;
}
return RETURN_OK;
}
ReturnValue_t PlocSupvHelper::handleExe(uint32_t timeout) {
ReturnValue_t result = RETURN_OK;
supv::ExecutionReport exeReport;
result = handleTmReception(&exeReport, supv::SIZE_EXE_REPORT, timeout);
if (result != RETURN_OK) {
triggerEvent(EXE_RECEPTION_FAILURE, result, static_cast<uint32_t>(rememberApid));
sif::warning << "PlocSupvHelper::handleExe: Error in reception of execution report"
<< std::endl;
return result;
}
result = exeReport.checkApid();
if (result != RETURN_OK) {
if (result == SupvReturnValuesIF::RECEIVED_EXE_FAILURE) {
triggerEvent(SUPV_EXE_FAILURE_REPORT, static_cast<uint32_t>(exeReport.getRefApid()));
} else if (result == SupvReturnValuesIF::INVALID_APID) {
triggerEvent(SUPV_EXE_INVALID_APID, static_cast<uint32_t>(rememberApid));
}
return result;
}
return RETURN_OK;
}
ReturnValue_t PlocSupvHelper::handleTmReception(supv::TmPacket* tmPacket, size_t remainingBytes,
uint32_t timeout) {
ReturnValue_t result = RETURN_OK;
size_t readBytes = 0;
size_t currentBytes = 0;
Countdown countdown(timeout);
while (!countdown.hasTimedOut()) {
result = receive(tmPacket->getWholeData() + readBytes, &currentBytes, remainingBytes);
if (result != RETURN_OK) {
return result;
}
readBytes += currentBytes;
remainingBytes = remainingBytes - currentBytes;
if (remainingBytes == 0) {
break;
}
}
if (remainingBytes != 0) {
sif::warning << "PlocSupvHelper::handleTmReception: Failed to read " << std::dec
<< remainingBytes << " bytes" << std::endl;
return RETURN_FAILED;
}
result = tmPacket->checkCrc();
if (result != RETURN_OK) {
sif::warning << "PlocSupvHelper::handleTmReception: CRC check failed" << std::endl;
return result;
}
return result;
}
ReturnValue_t PlocSupvHelper::receive(uint8_t* data, size_t* readBytes, size_t requestBytes) {
ReturnValue_t result = RETURN_OK;
uint8_t* buffer = nullptr;
result = uartComIF->requestReceiveMessage(comCookie, requestBytes);
if (result != RETURN_OK) {
sif::warning << "PlocSupvHelper::receive: Failed to request reply" << std::endl;
triggerEvent(SUPV_HELPER_REQUESTING_REPLY_FAILED, result,
static_cast<uint32_t>(static_cast<uint32_t>(internalState)));
return RETURN_FAILED;
}
result = uartComIF->readReceivedMessage(comCookie, &buffer, readBytes);
if (result != RETURN_OK) {
sif::warning << "PlocSupvHelper::receive: Failed to read received message" << std::endl;
triggerEvent(SUPV_HELPER_READING_REPLY_FAILED, result, static_cast<uint32_t>(internalState));
return RETURN_FAILED;
}
if (*readBytes > 0) {
std::memcpy(data, buffer, *readBytes);
} else {
TaskFactory::delayTask(40);
}
return result;
}
ReturnValue_t PlocSupvHelper::calcImageCrc() {
ReturnValue_t result = RETURN_OK;
#ifdef XIPHOS_Q7S
result = FilesystemHelper::checkPath(update.file);
#endif
if (result != RETURN_OK) {
sif::warning << "PlocSupvHelper::calcImageCrc: File " << update.file << " does not exist"
<< std::endl;
return result;
}
std::ifstream file(update.file, std::ifstream::binary);
uint16_t remainder = CRC16_INIT;
uint8_t input;
#if OBSW_DEBUG_PLOC_SUPERVISOR == 1
ProgressPrinter progress("Supervisor update crc calculation", update.length,
ProgressPrinter::ONE_PERCENT);
#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */
uint32_t byteCount = 0;
for (byteCount = 0; byteCount < update.length; byteCount++) {
file.seekg(byteCount, file.beg);
file.read(reinterpret_cast<char*>(&input), 1);
remainder = CRC::crc16ccitt(&input, sizeof(input), remainder);
#if OBSW_DEBUG_PLOC_SUPERVISOR == 1
progress.print(byteCount);
#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */
}
#if OBSW_DEBUG_PLOC_SUPERVISOR == 1
progress.print(byteCount);
#endif /* OBSW_DEBUG_PLOC_SUPERVISOR == 1 */
file.close();
update.crc = remainder;
return result;
}
ReturnValue_t PlocSupvHelper::handleCheckMemoryCommand() {
ReturnValue_t result = RETURN_OK;
// Verification of update write procedure
supv::CheckMemory packet(update.memoryId, update.startAddress, update.length);
result = sendCommand(packet);
if (result != RETURN_OK) {
return result;
}
result = handleAck();
if (result != RETURN_OK) {
return result;
}
supv::UpdateStatusReport updateStatusReport;
result = handleTmReception(&updateStatusReport,
static_cast<size_t>(updateStatusReport.getNominalSize()),
supv::recv_timeout::UPDATE_STATUS_REPORT);
if (result != RETURN_OK) {
sif::warning
<< "PlocSupvHelper::handleCheckMemoryCommand: Failed to receive update status report"
<< std::endl;
return result;
}
result = handleExe(CRC_EXECUTION_TIMEOUT);
if (result != RETURN_OK) {
return result;
}
result = updateStatusReport.parseDataField();
if (result != RETURN_OK) {
return result;
}
result = updateStatusReport.verifycrc(update.crc);
if (result != RETURN_OK) {
sif::warning << "PlocSupvHelper::handleCheckMemoryCommand: CRC failure. Expected CRC 0x"
<< std::hex << update.crc << " but received CRC 0x" << updateStatusReport.getCrc()
<< std::endl;
return result;
}
return result;
}
uint32_t PlocSupvHelper::getFileSize(std::string filename) {
std::ifstream file(filename, std::ifstream::binary);
file.seekg(0, file.end);
uint32_t size = file.tellg();
file.close();
return size;
}
ReturnValue_t PlocSupvHelper::handleEventBufferReception() {
ReturnValue_t result = RETURN_OK;
std::string filename = Filenaming::generateAbsoluteFilename(
eventBufferReq.path, eventBufferReq.filename, timestamping);
std::ofstream file(filename, std::ios_base::app | std::ios_base::out);
uint32_t packetsRead = 0;
size_t requestLen = 0;
supv::TmPacket tmPacket;
for (packetsRead = 0; packetsRead < NUM_EVENT_BUFFER_PACKETS; packetsRead++) {
if (terminate) {
triggerEvent(SUPV_EVENT_BUFFER_REQUEST_TERMINATED, packetsRead - 1);
file.close();
return PROCESS_TERMINATED;
}
if (packetsRead == NUM_EVENT_BUFFER_PACKETS - 1) {
requestLen = SIZE_EVENT_BUFFER_LAST_PACKET;
} else {
requestLen = SIZE_EVENT_BUFFER_FULL_PACKET;
}
result = handleTmReception(&tmPacket, requestLen);
if (result != RETURN_OK) {
sif::debug << "PlocSupvHelper::handleEventBufferReception: Failed while trying to read packet"
<< " " << packetsRead + 1 << std::endl;
file.close();
return result;
}
uint16_t apid = tmPacket.getAPID();
if (apid != supv::APID_MRAM_DUMP_TM) {
sif::warning << "PlocSupvHelper::handleEventBufferReception: Did not expect space packet "
<< "with APID 0x" << std::hex << apid << std::endl;
file.close();
return EVENT_BUFFER_REPLY_INVALID_APID;
}
file.write(reinterpret_cast<const char*>(tmPacket.getPacketData()),
tmPacket.getPayloadDataLength());
}
return result;
}

View File

@ -0,0 +1,241 @@
#ifndef BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_
#define BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_
#include <string>
#include "OBSWConfig.h"
#include "fsfw/devicehandlers/CookieIF.h"
#include "fsfw/objectmanager/SystemObject.h"
#include "fsfw/osal/linux/BinarySemaphore.h"
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
#include "fsfw/tasks/ExecutableObjectIF.h"
#include "fsfw_hal/linux/uart/UartComIF.h"
#include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h"
#ifdef XIPHOS_Q7S
#include "bsp_q7s/memory/SdCardManager.h"
#endif
/**
* @brief Helper class for supervisor of PLOC intended to accelerate large data transfers between
* the supervisor and the OBC.
* @author J. Meier
*/
class PlocSupvHelper : public SystemObject, public ExecutableObjectIF, public HasReturnvaluesIF {
public:
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_SUPV_HELPER;
//! [EXPORT] : [COMMENT] update failed
static const Event SUPV_UPDATE_FAILED = MAKE_EVENT(0, severity::LOW);
//! [EXPORT] : [COMMENT] update successful
static const Event SUPV_UPDATE_SUCCESSFUL = MAKE_EVENT(1, severity::LOW);
//! [EXPORT] : [COMMENT] Continue update command failed
static const Event SUPV_CONTINUE_UPDATE_FAILED = MAKE_EVENT(2, severity::LOW);
//! [EXPORT] : [COMMENT] Continue update command successful
static const Event SUPV_CONTINUE_UPDATE_SUCCESSFUL = MAKE_EVENT(3, severity::LOW);
//! [EXPORT] : [COMMENT] Terminated update procedure by command
static const Event TERMINATED_UPDATE_PROCEDURE = MAKE_EVENT(4, severity::LOW);
//! [EXPORT] : [COMMENT] Requesting event buffer was successful
static const Event SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL = MAKE_EVENT(5, severity::LOW);
//! [EXPORT] : [COMMENT] Requesting event buffer failed
static const Event SUPV_EVENT_BUFFER_REQUEST_FAILED = MAKE_EVENT(6, severity::LOW);
//! [EXPORT] : [COMMENT] Terminated event buffer request by command
//! P1: Number of packets read before process was terminated
static const Event SUPV_EVENT_BUFFER_REQUEST_TERMINATED = MAKE_EVENT(7, severity::LOW);
//! [EXPORT] : [COMMENT] Communication interface returned failure when trying to send the command
//! to the supervisor
//! P1: Return value returned by the communication interface sendMessage function
//! P2: Internal state of supervisor helper
static const Event SUPV_SENDING_COMMAND_FAILED = MAKE_EVENT(8, severity::LOW);
//! [EXPORT] : [COMMENT] Request receive message of communication interface failed
//! P1: Return value returned by the communication interface requestReceiveMessage function
//! P2: Internal state of supervisor helper
static const Event SUPV_HELPER_REQUESTING_REPLY_FAILED = MAKE_EVENT(9, severity::LOW);
//! [EXPORT] : [COMMENT] Reading receive message of communication interface failed
//! P1: Return value returned by the communication interface readingReceivedMessage function
//! P2: Internal state of supervisor helper
static const Event SUPV_HELPER_READING_REPLY_FAILED = MAKE_EVENT(10, severity::LOW);
//! [EXPORT] : [COMMENT] Did not receive acknowledgement report
//! P1: Number of bytes missing
//! P2: Internal state of MPSoC helper
static const Event SUPV_MISSING_ACK = MAKE_EVENT(11, severity::LOW);
//! [EXPORT] : [COMMENT] Supervisor did not receive execution report
//! P1: Number of bytes missing
//! P2: Internal state of supervisor helper
static const Event SUPV_MISSING_EXE = MAKE_EVENT(12, severity::LOW);
//! [EXPORT] : [COMMENT] Supervisor received acknowledgment failure report
//! P1: Internal state of supervisor helper
static const Event SUPV_ACK_FAILURE_REPORT = MAKE_EVENT(13, severity::LOW);
//! [EXPORT] : [COMMENT] Execution report failure
//! P1:
static const Event SUPV_EXE_FAILURE_REPORT = MAKE_EVENT(14, severity::LOW);
//! [EXPORT] : [COMMENT] Supervisor expected acknowledgment report but received space packet with
//! other apid P1: Apid of received space packet P2: Internal state of supervisor helper
static const Event SUPV_ACK_INVALID_APID = MAKE_EVENT(15, severity::LOW);
//! [EXPORT] : [COMMENT] Supervisor helper expected execution report but received space packet
//! with other apid P1: Apid of received space packet P2: Internal state of supervisor helper
static const Event SUPV_EXE_INVALID_APID = MAKE_EVENT(16, severity::LOW);
//! [EXPORT] : [COMMENT] Failed to receive acknowledgment report
//! P1: Return value
//! P2: Apid of command for which the reception of the acknowledgment report failed
static const Event ACK_RECEPTION_FAILURE = MAKE_EVENT(17, severity::LOW);
//! [EXPORT] : [COMMENT] Failed to receive execution report
//! P1: Return value
//! P2: Apid of command for which the reception of the execution report failed
static const Event EXE_RECEPTION_FAILURE = MAKE_EVENT(18, severity::LOW);
//! [EXPORT] : [COMMENT] Update procedure failed when sending packet with number P1
//! P1: Packet number for which the memory write command fails
static const Event WRITE_MEMORY_FAILED = MAKE_EVENT(19, severity::LOW);
PlocSupvHelper(object_id_t objectId);
virtual ~PlocSupvHelper();
ReturnValue_t initialize() override;
ReturnValue_t performOperation(uint8_t operationCode = 0) override;
ReturnValue_t setComIF(UartComIF* uartComfIF_);
void setComCookie(CookieIF* comCookie_);
/**
* @brief Starts update procedure
*
* @param file File containing the update data
* @param memoryId ID of the memory where to write to
* @param startAddress Address where to write data
*
* @return RETURN_OK if successful, otherwise error return value
*/
ReturnValue_t startUpdate(std::string file, uint8_t memoryId, uint32_t startAddress);
/**
* @brief This initiate the continuation of a failed update.
*/
void initiateUpdateContinuation();
/**
* @brief Calling this function will initiate the procedure to request the event buffer
*/
ReturnValue_t startEventbBufferRequest(std::string path);
/**
* @brief Can be used to interrupt a running data transfer.
*/
void stopProcess();
private:
static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_SUPV_HELPER;
//! [EXPORT] : [COMMENT] File accidentally close
static const ReturnValue_t FILE_CLOSED_ACCIDENTALLY = MAKE_RETURN_CODE(0xA0);
//! [EXPORT] : [COMMENT] Process has been terminated by command
static const ReturnValue_t PROCESS_TERMINATED = MAKE_RETURN_CODE(0xA1);
//! [EXPORT] : [COMMENT] Received command with invalid pathname
static const ReturnValue_t PATH_NOT_EXISTS = MAKE_RETURN_CODE(0xA2);
//! [EXPORT] : [COMMENT] Expected event buffer TM but received space packet with other APID
static const ReturnValue_t EVENT_BUFFER_REPLY_INVALID_APID = MAKE_RETURN_CODE(0xA3);
static const uint16_t CRC16_INIT = 0xFFFF;
// Event buffer reply will carry 24 space packets with 1016 bytes and one space packet with
// 192 bytes
static const uint8_t NUM_EVENT_BUFFER_PACKETS = 25;
static const size_t SIZE_EVENT_BUFFER_FULL_PACKET = 1024;
static const size_t SIZE_EVENT_BUFFER_LAST_PACKET = 200;
static const uint32_t CRC_EXECUTION_TIMEOUT = 60000;
static const uint32_t PREPARE_UPDATE_EXECUTION_REPORT = 2000;
struct Update {
uint8_t memoryId;
uint32_t startAddress;
// Absolute name of file containing update data
std::string file;
// Size of update
uint32_t length;
uint32_t crc;
size_t remainingSize;
size_t bytesWritten;
uint32_t packetNum;
uint16_t sequenceCount;
};
struct Update update;
struct EventBufferRequest {
std::string path = "";
// Default name of file where event buffer data will be written to. Timestamp will be added to
// name when new file is created
std::string filename = "event-buffer.bin";
};
EventBufferRequest eventBufferReq;
enum class InternalState { IDLE, UPDATE, CONTINUE_UPDATE, REQUEST_EVENT_BUFFER };
InternalState internalState = InternalState::IDLE;
BinarySemaphore semaphore;
#ifdef XIPHOS_Q7S
SdCardManager* sdcMan = nullptr;
#endif
uint8_t commandBuffer[supv::MAX_COMMAND_SIZE];
bool terminate = false;
/**
* Communication interface responsible for data transactions between OBC and Supervisor.
*/
UartComIF* uartComIF = nullptr;
// Communication cookie. Must be set by the supervisor Handler
CookieIF* comCookie = nullptr;
bool timestamping = true;
// Remembers APID to know at which command a procedure failed
uint16_t rememberApid = 0;
ReturnValue_t performUpdate();
ReturnValue_t continueUpdate();
ReturnValue_t writeUpdatePackets();
ReturnValue_t performEventBufferRequest();
ReturnValue_t handlePacketTransmission(SpacePacket& packet,
uint32_t timeoutExecutionReport = 60000);
ReturnValue_t sendCommand(SpacePacket& packet);
/**
* @brief Function which reads form the communication interface
*
* @param data Pointer to buffer where read data will be written to
* @param raedBytes Actual number of bytes read
* @param requestBytes Number of bytes to read
*/
ReturnValue_t receive(uint8_t* data, size_t* readBytes, size_t requestBytes);
ReturnValue_t handleAck();
ReturnValue_t handleExe(uint32_t timeout = 1000);
/**
* @brief Handles reading of TM packets from the communication interface
*
* @param tmPacket Pointer to space packet where received data will be written to
* @param reaminingBytes Number of bytes to read in the space packet
* @param timeout Receive timeout in milliseconds
*
* @note It can take up to 70 seconds until the supervisor replies with an acknowledgment
* failure report.
*/
ReturnValue_t handleTmReception(supv::TmPacket* tmPacket, size_t remainingBytes,
uint32_t timeout = 70000);
ReturnValue_t selectMemory();
ReturnValue_t prepareUpdate();
ReturnValue_t eraseMemory();
// Calculates CRC over image. Will be used for verification after update writing has
// finished.
ReturnValue_t calcImageCrc();
ReturnValue_t handleCheckMemoryCommand();
/**
* @brief Return size of file with name filename
*
* @param filename
*
* @return The size of the file
*/
uint32_t getFileSize(std::string filename);
ReturnValue_t handleEventBufferReception();
};
#endif /* BSP_Q7S_DEVICES_PLOCSUPVHELPER_H_ */

View File

@ -1,385 +0,0 @@
#include "PlocUpdater.h"
#include <filesystem>
#include <fstream>
#include <string>
#include "fsfw/ipc/QueueFactory.h"
PlocUpdater::PlocUpdater(object_id_t objectId)
: SystemObject(objectId), commandActionHelper(this), actionHelper(this, nullptr) {
auto mqArgs = MqArgs(this->getObjectId());
commandQueue = QueueFactory::instance()->createMessageQueue(
QUEUE_SIZE, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
}
PlocUpdater::~PlocUpdater() {}
ReturnValue_t PlocUpdater::initialize() {
#ifdef XIPHOS_Q7S
sdcMan = SdCardManager::instance();
#endif
ReturnValue_t result = SystemObject::initialize();
if (result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
result = commandActionHelper.initialize();
if (result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
result = actionHelper.initialize(commandQueue);
if (result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t PlocUpdater::performOperation(uint8_t operationCode) {
readCommandQueue();
doStateMachine();
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t PlocUpdater::executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
const uint8_t* data, size_t size) {
ReturnValue_t result = RETURN_FAILED;
if (state != State::IDLE) {
return IS_BUSY;
}
if (size > MAX_PLOC_UPDATE_PATH) {
return NAME_TOO_LONG;
}
switch (actionId) {
case UPDATE_A_UBOOT:
image = Image::A;
partition = Partition::UBOOT;
break;
case UPDATE_A_BITSTREAM:
image = Image::A;
partition = Partition::BITSTREAM;
break;
case UPDATE_A_LINUX:
image = Image::A;
partition = Partition::LINUX_OS;
break;
case UPDATE_A_APP_SW:
image = Image::A;
partition = Partition::APP_SW;
break;
case UPDATE_B_UBOOT:
image = Image::B;
partition = Partition::UBOOT;
break;
case UPDATE_B_BITSTREAM:
image = Image::B;
partition = Partition::BITSTREAM;
break;
case UPDATE_B_LINUX:
image = Image::B;
partition = Partition::LINUX_OS;
break;
case UPDATE_B_APP_SW:
image = Image::B;
partition = Partition::APP_SW;
break;
default:
return INVALID_ACTION_ID;
}
result = getImageLocation(data, size);
if (result != RETURN_OK) {
return result;
}
state = State::UPDATE_AVAILABLE;
return EXECUTION_FINISHED;
}
MessageQueueId_t PlocUpdater::getCommandQueue() const { return commandQueue->getId(); }
MessageQueueIF* PlocUpdater::getCommandQueuePtr() { return commandQueue; }
void PlocUpdater::readCommandQueue() {
CommandMessage message;
ReturnValue_t result;
for (result = commandQueue->receiveMessage(&message); result == HasReturnvaluesIF::RETURN_OK;
result = commandQueue->receiveMessage(&message)) {
if (result != RETURN_OK) {
continue;
}
result = actionHelper.handleActionMessage(&message);
if (result == HasReturnvaluesIF::RETURN_OK) {
continue;
}
result = commandActionHelper.handleReply(&message);
if (result == HasReturnvaluesIF::RETURN_OK) {
continue;
}
}
}
void PlocUpdater::doStateMachine() {
switch (state) {
case State::IDLE:
break;
case State::UPDATE_AVAILABLE:
commandUpdateAvailable();
break;
case State::UPDATE_TRANSFER:
commandUpdatePacket();
break;
case State::UPDATE_VERIFY:
commandUpdateVerify();
break;
case State::COMMAND_EXECUTING:
break;
default:
break;
}
}
ReturnValue_t PlocUpdater::checkNameLength(size_t size) {
if (size > MAX_PLOC_UPDATE_PATH) {
return NAME_TOO_LONG;
}
return RETURN_OK;
}
ReturnValue_t PlocUpdater::getImageLocation(const uint8_t* data, size_t size) {
ReturnValue_t result = checkNameLength(size);
if (result != RETURN_OK) {
return result;
}
#ifdef XIPHOS_Q7S
// Check if file is stored on SD card and if associated SD card is mounted
if (std::string(reinterpret_cast<const char*>(data), SD_PREFIX_LENGTH) ==
std::string(SdCardManager::SD_0_MOUNT_POINT)) {
if (!sdcMan->isSdCardMounted(sd::SLOT_0)) {
sif::warning << "PlocUpdater::getImageLocation: SD card 0 not mounted" << std::endl;
return SD_NOT_MOUNTED;
}
} else if (std::string(reinterpret_cast<const char*>(data), SD_PREFIX_LENGTH) ==
std::string(SdCardManager::SD_1_MOUNT_POINT)) {
if (!sdcMan->isSdCardMounted(sd::SLOT_0)) {
sif::warning << "PlocUpdater::getImageLocation: SD card 1 not mounted" << std::endl;
return SD_NOT_MOUNTED;
}
} else {
// update image not stored on SD card
}
#endif /* BOARD_TE0720 == 0 */
updateFile = std::string(reinterpret_cast<const char*>(data), size);
// Check if file exists
if (not std::filesystem::exists(updateFile)) {
return FILE_NOT_EXISTS;
}
return RETURN_OK;
}
void PlocUpdater::stepSuccessfulReceived(ActionId_t actionId, uint8_t step) {}
void PlocUpdater::stepFailedReceived(ActionId_t actionId, uint8_t step, ReturnValue_t returnCode) {}
void PlocUpdater::dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) {}
void PlocUpdater::completionSuccessfulReceived(ActionId_t actionId) {
switch (pendingCommand) {
case (supv::UPDATE_AVAILABLE):
state = State::UPDATE_TRANSFER;
break;
case (supv::UPDATE_IMAGE_DATA):
if (remainingPackets == 0) {
packetsSent = 0; // Reset packets sent variable for next update sequence
state = State::UPDATE_VERIFY;
} else {
state = State::UPDATE_TRANSFER;
}
break;
case (supv::UPDATE_VERIFY):
triggerEvent(UPDATE_FINISHED);
state = State::IDLE;
pendingCommand = supv::NONE;
break;
default:
state = State::IDLE;
break;
}
}
void PlocUpdater::completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) {
switch (pendingCommand) {
case (supv::UPDATE_AVAILABLE): {
triggerEvent(UPDATE_AVAILABLE_FAILED);
break;
}
case (supv::UPDATE_IMAGE_DATA): {
triggerEvent(UPDATE_TRANSFER_FAILED, packetsSent);
break;
}
case (supv::UPDATE_VERIFY): {
triggerEvent(UPDATE_VERIFY_FAILED);
break;
}
default:
break;
}
state = State::IDLE;
}
void PlocUpdater::commandUpdateAvailable() {
ReturnValue_t result = RETURN_OK;
if (not std::filesystem::exists(updateFile)) {
triggerEvent(UPDATE_FILE_NOT_EXISTS, static_cast<uint8_t>(state));
state = State::IDLE;
return;
}
std::ifstream file(updateFile, std::ifstream::binary);
file.seekg(0, file.end);
imageSize = static_cast<size_t>(file.tellg());
file.close();
numOfUpdatePackets = imageSize / MAX_SP_DATA;
if (imageSize % MAX_SP_DATA) {
numOfUpdatePackets++;
}
remainingPackets = numOfUpdatePackets;
packetsSent = 0;
calcImageCrc();
supv::UpdateInfo packet(supv::APID_UPDATE_AVAILABLE, static_cast<uint8_t>(image),
static_cast<uint8_t>(partition), imageSize, imageCrc, numOfUpdatePackets);
result =
commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, supv::UPDATE_AVAILABLE,
packet.getWholeData(), packet.getFullSize());
if (result != RETURN_OK) {
sif::warning << "PlocUpdater::commandUpdateAvailable: Failed to send update available"
<< " packet to supervisor handler" << std::endl;
triggerEvent(ACTION_COMMANDING_FAILED, result, supv::UPDATE_AVAILABLE);
state = State::IDLE;
pendingCommand = supv::NONE;
return;
}
pendingCommand = supv::UPDATE_AVAILABLE;
state = State::COMMAND_EXECUTING;
return;
}
void PlocUpdater::commandUpdatePacket() {
ReturnValue_t result = RETURN_OK;
uint16_t payloadLength = 0;
if (not std::filesystem::exists(updateFile)) {
triggerEvent(UPDATE_FILE_NOT_EXISTS, static_cast<uint8_t>(state), packetsSent);
state = State::IDLE;
return;
}
std::ifstream file(updateFile, std::ifstream::binary);
file.seekg(packetsSent * MAX_SP_DATA, file.beg);
if (remainingPackets == 1) {
payloadLength = imageSize - static_cast<uint16_t>(file.tellg());
} else {
payloadLength = MAX_SP_DATA;
}
supv::UpdatePacket packet(payloadLength);
file.read(reinterpret_cast<char*>(packet.getDataFieldPointer()), payloadLength);
file.close();
// sequence count of first packet is 1
packet.setPacketSequenceCount((packetsSent + 1) & supv::SEQUENCE_COUNT_MASK);
if (numOfUpdatePackets > 1) {
adjustSequenceFlags(packet);
}
packet.makeCrc();
result =
commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, supv::UPDATE_IMAGE_DATA,
packet.getWholeData(), packet.getFullSize());
if (result != RETURN_OK) {
sif::warning << "PlocUpdater::commandUpdateAvailable: Failed to send update"
<< " packet to supervisor handler" << std::endl;
triggerEvent(ACTION_COMMANDING_FAILED, result, supv::UPDATE_IMAGE_DATA);
state = State::IDLE;
pendingCommand = supv::NONE;
return;
}
remainingPackets--;
packetsSent++;
pendingCommand = supv::UPDATE_IMAGE_DATA;
state = State::COMMAND_EXECUTING;
}
void PlocUpdater::commandUpdateVerify() {
ReturnValue_t result = RETURN_OK;
supv::UpdateInfo packet(supv::APID_UPDATE_VERIFY, static_cast<uint8_t>(image),
static_cast<uint8_t>(partition), imageSize, imageCrc, numOfUpdatePackets);
result = commandActionHelper.commandAction(objects::PLOC_SUPERVISOR_HANDLER, supv::UPDATE_VERIFY,
packet.getWholeData(), packet.getFullSize());
if (result != RETURN_OK) {
sif::warning << "PlocUpdater::commandUpdateAvailable: Failed to send update available"
<< " packet to supervisor handler" << std::endl;
triggerEvent(ACTION_COMMANDING_FAILED, result, supv::UPDATE_VERIFY);
state = State::IDLE;
pendingCommand = supv::NONE;
return;
}
state = State::COMMAND_EXECUTING;
pendingCommand = supv::UPDATE_VERIFY;
return;
}
void PlocUpdater::calcImageCrc() {
std::ifstream file(updateFile, std::ifstream::binary);
file.seekg(0, file.end);
uint32_t count;
uint32_t bit;
uint32_t remainder = INITIAL_REMAINDER_32;
char input;
for (count = 0; count < imageSize; count++) {
file.seekg(count, file.beg);
file.read(&input, 1);
remainder ^= (input << 16);
for (bit = 8; bit > 0; --bit) {
if (remainder & TOPBIT_32) {
remainder = (remainder << 1) ^ POLYNOMIAL_32;
} else {
remainder = (remainder << 1);
}
}
}
file.close();
imageCrc = (remainder ^ FINAL_XOR_VALUE_32);
}
void PlocUpdater::adjustSequenceFlags(supv::UpdatePacket& packet) {
if (packetsSent == 0) {
packet.setSequenceFlags(static_cast<uint8_t>(supv::SequenceFlags::FIRST_PKT));
} else if (remainingPackets == 1) {
packet.setSequenceFlags(static_cast<uint8_t>(supv::SequenceFlags::LAST_PKT));
} else {
packet.setSequenceFlags(static_cast<uint8_t>(supv::SequenceFlags::CONTINUED_PKT));
}
}

View File

@ -1,174 +0,0 @@
#ifndef MISSION_DEVICES_PLOCUPDATER_H_
#define MISSION_DEVICES_PLOCUPDATER_H_
#include <linux/devices/devicedefinitions/PlocSupervisorDefinitions.h>
#include "OBSWConfig.h"
#include "bsp_q7s/memory/SdCardManager.h"
#include "eive/definitions.h"
#include "fsfw/action/ActionHelper.h"
#include "fsfw/action/CommandActionHelper.h"
#include "fsfw/action/CommandsActionsIF.h"
#include "fsfw/action/HasActionsIF.h"
#include "fsfw/objectmanager/SystemObject.h"
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
#include "fsfw/tasks/ExecutableObjectIF.h"
#include "fsfw/tmtcpacket/SpacePacket.h"
#include "linux/devices/devicedefinitions/PlocSupervisorDefinitions.h"
#include "linux/fsfwconfig/objects/systemObjectList.h"
/**
* @brief An object of this class can be used to perform the software updates of the PLOC. The
* software update will be read from one of the SD cards, split into multiple space
* packets and sent to the PlocSupervisorHandler.
*
* @details The MPSoC has two boot memories (NVM0 and NVM1) where each stores two images (Partition
* A and Partition B)
*
* @author J. Meier
*/
class PlocUpdater : public SystemObject,
public HasActionsIF,
public ExecutableObjectIF,
public HasReturnvaluesIF,
public CommandsActionsIF {
public:
static const ActionId_t UPDATE_A_UBOOT = 0;
static const ActionId_t UPDATE_A_BITSTREAM = 1;
static const ActionId_t UPDATE_A_LINUX = 2;
static const ActionId_t UPDATE_A_APP_SW = 3;
static const ActionId_t UPDATE_B_UBOOT = 4;
static const ActionId_t UPDATE_B_BITSTREAM = 5;
static const ActionId_t UPDATE_B_LINUX = 6;
static const ActionId_t UPDATE_B_APP_SW = 7;
PlocUpdater(object_id_t objectId);
virtual ~PlocUpdater();
ReturnValue_t performOperation(uint8_t operationCode = 0) override;
ReturnValue_t executeAction(ActionId_t actionId, MessageQueueId_t commandedBy,
const uint8_t* data, size_t size);
MessageQueueId_t getCommandQueue() const;
ReturnValue_t initialize() override;
MessageQueueIF* getCommandQueuePtr() override;
void stepSuccessfulReceived(ActionId_t actionId, uint8_t step) override;
void stepFailedReceived(ActionId_t actionId, uint8_t step, ReturnValue_t returnCode) override;
void dataReceived(ActionId_t actionId, const uint8_t* data, uint32_t size) override;
void completionSuccessfulReceived(ActionId_t actionId) override;
void completionFailedReceived(ActionId_t actionId, ReturnValue_t returnCode) override;
private:
static const uint8_t INTERFACE_ID = CLASS_ID::PLOC_UPDATER;
//! [EXPORT] : [COMMENT] Updater is already performing an update
static const ReturnValue_t UPDATER_BUSY = MAKE_RETURN_CODE(0xA0);
//! [EXPORT] : [COMMENT] Received update command with invalid path string (too long).
static const ReturnValue_t NAME_TOO_LONG = MAKE_RETURN_CODE(0xA1);
//! [EXPORT] : [COMMENT] Received command to initiate update but SD card with update image not
//! mounted.
static const ReturnValue_t SD_NOT_MOUNTED = MAKE_RETURN_CODE(0xA2);
//! [EXPORT] : [COMMENT] Update file received with update command does not exist.
static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xA3);
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PLOC_UPDATER;
//! [EXPORT] : [COMMENT] Try to read update file but the file does not exist.
//! P1: Indicates in which state the file read fails
//! P2: During the update transfer the second parameter gives information about the number of
//! already sent packets
static const Event UPDATE_FILE_NOT_EXISTS = MAKE_EVENT(0, severity::LOW);
//! [EXPORT] : [COMMENT] Failed to send command to supervisor handler
//! P1: Return value of CommandActionHelper::commandAction
//! P2: Action ID of command to send
static const Event ACTION_COMMANDING_FAILED = MAKE_EVENT(1, severity::LOW);
//! [EXPORT] : [COMMENT] Supervisor handler replied action message indicating a command execution
//! failure of the update available command
static const Event UPDATE_AVAILABLE_FAILED = MAKE_EVENT(2, severity::LOW);
//! [EXPORT] : [COMMENT] Supervisor handler failed to transfer an update space packet.
//! P1: Parameter holds the number of update packets already sent (inclusive the failed packet)
static const Event UPDATE_TRANSFER_FAILED = MAKE_EVENT(3, severity::LOW);
//! [EXPORT] : [COMMENT] Supervisor failed to execute the update verify command.
static const Event UPDATE_VERIFY_FAILED = MAKE_EVENT(4, severity::LOW);
//! [EXPORT] : [COMMENT] MPSoC update successful completed
static const Event UPDATE_FINISHED = MAKE_EVENT(5, severity::INFO);
static const uint32_t QUEUE_SIZE = config::PLOC_UPDATER_QUEUE_SIZE;
static const size_t MAX_PLOC_UPDATE_PATH = 50;
static const size_t SD_PREFIX_LENGTH = 8;
// Maximum size of update payload data per space packet (max size of space packet is 1024 bytes)
static const size_t MAX_SP_DATA = 1016;
static const uint32_t TOPBIT_32 = (1 << 31);
static const uint32_t POLYNOMIAL_32 = 0x04C11DB7;
static const uint32_t INITIAL_REMAINDER_32 = 0xFFFFFFFF;
static const uint32_t FINAL_XOR_VALUE_32 = 0xFFFFFFFF;
MessageQueueIF* commandQueue = nullptr;
#ifdef XIPHOS_Q7S
SdCardManager* sdcMan = nullptr;
#endif
CommandActionHelper commandActionHelper;
ActionHelper actionHelper;
enum class State : uint8_t {
IDLE,
UPDATE_AVAILABLE,
UPDATE_TRANSFER,
UPDATE_VERIFY,
COMMAND_EXECUTING
};
State state = State::IDLE;
ActionId_t pendingCommand = supv::NONE;
enum class Image : uint8_t { NONE, A, B };
Image image = Image::NONE;
enum class Partition : uint8_t { NONE, UBOOT, BITSTREAM, LINUX_OS, APP_SW };
Partition partition = Partition::NONE;
uint32_t packetsSent = 0;
uint32_t remainingPackets = 0;
// Number of packets required to transfer the update image
uint32_t numOfUpdatePackets = 0;
std::string updateFile;
uint32_t imageSize = 0;
uint32_t imageCrc = 0;
void readCommandQueue();
void doStateMachine();
/**
* @brief Extracts the path and name of the update image from the service 8 command data.
*/
ReturnValue_t getImageLocation(const uint8_t* data, size_t size);
ReturnValue_t checkNameLength(size_t size);
/**
* @brief Prepares and sends update available command to PLOC supervisor handler.
*/
void commandUpdateAvailable();
/**
* @brief Prepares and sends and update packet to the PLOC supervisor handler.
*/
void commandUpdatePacket();
/**
* @brief Prepares and sends the update verification packet to the PLOC supervisor handler.
*/
void commandUpdateVerify();
void calcImageCrc();
void adjustSequenceFlags(supv::UpdatePacket& packet);
};
#endif /* MISSION_DEVICES_PLOCUPDATER_H_ */

View File

@ -1,7 +1,4 @@
target_sources(${OBSW_NAME} PRIVATE
StarTrackerHandler.cpp
StarTrackerJsonCommands.cpp
ArcsecDatalinkLayer.cpp
ArcsecJsonParamBase.cpp
StrHelper.cpp
)
target_sources(
${OBSW_NAME}
PRIVATE StarTrackerHandler.cpp StarTrackerJsonCommands.cpp
ArcsecDatalinkLayer.cpp ArcsecJsonParamBase.cpp StrHelper.cpp)

View File

@ -6,6 +6,7 @@
#include "OBSWConfig.h"
#include "fsfw/timemanager/Countdown.h"
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
#include "mission/utility/Filenaming.h"
#include "mission/utility/ProgressPrinter.h"
#include "mission/utility/Timestamp.h"
@ -181,7 +182,8 @@ ReturnValue_t StrHelper::performImageDownload() {
struct DownloadActionRequest downloadReq;
uint32_t size = 0;
uint32_t retries = 0;
std::string image = makeFullFilename(downloadImage.path, downloadImage.filename);
std::string image = Filenaming::generateAbsoluteFilename(downloadImage.path,
downloadImage.filename, timestamping);
std::ofstream file(image, std::ios_base::out);
if (not std::filesystem::exists(image)) {
return FILE_CREATION_FAILED;
@ -400,7 +402,8 @@ ReturnValue_t StrHelper::performFlashRead() {
uint32_t size = 0;
uint32_t retries = 0;
Timestamp timestamp;
std::string fullname = makeFullFilename(flashRead.path, flashRead.filename);
std::string fullname =
Filenaming::generateAbsoluteFilename(flashRead.path, flashRead.filename, timestamping);
std::ofstream file(fullname, std::ios_base::app | std::ios_base::out);
if (not std::filesystem::exists(fullname)) {
return FILE_CREATION_FAILED;
@ -588,14 +591,3 @@ ReturnValue_t StrHelper::unlockAndEraseRegions(uint32_t from, uint32_t to) {
}
return result;
}
std::string StrHelper::makeFullFilename(std::string path, std::string filename) {
std::string image;
Timestamp timestamp;
if (timestamping) {
image = path + "/" + timestamp.str() + filename;
} else {
image = path + "/" + filename;
}
return image;
}

View File

@ -173,8 +173,7 @@ class StrHelper : public SystemObject, public ExecutableObjectIF, public HasRetu
static const size_t SIZE_IMAGE_PART = 1024;
static const uint32_t FLASH_REGION_SIZE = 0x20000;
class ImageDownload {
public:
struct ImageDownload {
static const uint32_t LAST_POSITION = 4095;
};
@ -199,15 +198,13 @@ class StrHelper : public SystemObject, public ExecutableObjectIF, public HasRetu
BinarySemaphore semaphore;
class UploadImage {
public:
struct UploadImage {
// Name including absolute path of image to upload
std::string uploadFile;
};
UploadImage uploadImage;
class DownloadImage {
public:
struct DownloadImage {
// Path where the downloaded image will be stored
std::string path;
// Default name of downloaded image, can be changed via command
@ -215,8 +212,7 @@ class StrHelper : public SystemObject, public ExecutableObjectIF, public HasRetu
};
DownloadImage downloadImage;
class FlashWrite {
public:
struct FlashWrite {
// File which contains data to write when executing the flash write command
std::string fullname;
// The first region to write to
@ -229,8 +225,7 @@ class StrHelper : public SystemObject, public ExecutableObjectIF, public HasRetu
};
FlashWrite flashWrite;
class FlashRead {
public:
struct FlashRead {
// Path where the file containing the read data will be stored
std::string path = "";
// Default name of file containing the data read from flash, can be changed via command
@ -349,16 +344,6 @@ class StrHelper : public SystemObject, public ExecutableObjectIF, public HasRetu
*
*/
ReturnValue_t unlockAndEraseRegions(uint32_t from, uint32_t to);
/**
* @brief Creates full filename either with timestamp or without
*
* @param path Path where to create the file
* @param filename Name fo the file
*
* @return Full filename
*/
std::string makeFullFilename(std::string path, std::string filename);
};
#endif /* BSP_Q7S_DEVICES_STRHELPER_H_ */

View File

@ -1,28 +1,16 @@
target_sources(${OBSW_NAME} PRIVATE
ipc/MissionMessageTypes.cpp
pollingsequence/pollingSequenceFactory.cpp
)
target_sources(${OBSW_NAME} PRIVATE ipc/MissionMessageTypes.cpp
pollingsequence/pollingSequenceFactory.cpp)
target_include_directories(${OBSW_NAME} PUBLIC
${CMAKE_CURRENT_SOURCE_DIR}
)
target_include_directories(${OBSW_NAME} PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
# If a special translation file for object IDs exists, compile it.
if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/objects/translateObjects.cpp")
target_sources(${OBSW_NAME} PRIVATE
objects/translateObjects.cpp
)
target_sources(${UNITTEST_NAME} PRIVATE
objects/translateObjects.cpp
)
target_sources(${OBSW_NAME} PRIVATE objects/translateObjects.cpp)
target_sources(${UNITTEST_NAME} PRIVATE objects/translateObjects.cpp)
endif()
# If a special translation file for events exists, compile it.
if(EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/objects/translateObjects.cpp")
target_sources(${OBSW_NAME} PRIVATE
events/translateEvents.cpp
)
target_sources(${UNITTEST_NAME} PRIVATE
events/translateEvents.cpp
)
target_sources(${OBSW_NAME} PRIVATE events/translateEvents.cpp)
target_sources(${UNITTEST_NAME} PRIVATE events/translateEvents.cpp)
endif()

View File

@ -76,9 +76,4 @@ static constexpr size_t FSFW_MAX_TM_PACKET_SIZE = 2048;
#define FSFW_HAL_I2C_WIRETAPPING 0
#define FSFW_DEV_HYPERION_GPS_CREATE_NMEA_CSV 0
#define FSFW_HAL_L3GD20_GYRO_DEBUG 0
#define FSFW_HAL_RM3100_MGM_DEBUG 0
#define FSFW_HAL_LIS3MDL_MGM_DEBUG 0
#define FSFW_HAL_ADIS1650X_GYRO_DEBUG 0
#endif /* CONFIG_FSFWCONFIG_H_ */

View File

@ -1,210 +0,0 @@
/**
* @brief This file can be used to add preprocessor define for conditional
* code inclusion exclusion or various other project constants and
* properties in one place.
*/
#ifndef FSFWCONFIG_OBSWCONFIG_H_
#define FSFWCONFIG_OBSWCONFIG_H_
#cmakedefine RASPBERRY_PI
#cmakedefine XIPHOS_Q7S
#cmakedefine BEAGLEBONEBLACK
#cmakedefine EGSE
#cmakedefine TE0720_1CFA
#include "commonConfig.h"
#include "OBSWVersion.h"
/* These defines should be disabled for mission code but are useful for
debugging. */
#define OBSW_VERBOSE_LEVEL 1
#define Q7S_EM 0
/*******************************************************************/
/** All of the following flags should be enabled for mission code */
/*******************************************************************/
//! Timers can mess up the code when debugging
//! All of this should be enabled for mission code!
#if defined XIPHOS_Q7S
#define Q7S_EM 0
#define OBSW_USE_CCSDS_IP_CORE 1
// Set to 1 if all telemetry should be sent to the PTME IP Core
#define OBSW_TM_TO_PTME 0
// Set to 1 if telecommands are received via the PDEC IP Core
#define OBSW_TC_FROM_PDEC 0
#define OBSW_ENABLE_TIMERS 1
#define OBSW_ADD_MGT 1
#define OBSW_ADD_BPX_BATTERY_HANDLER 1
#define OBSW_ADD_STAR_TRACKER @OBSW_ADD_STAR_TRACKER@
#define OBSW_ADD_PLOC_SUPERVISOR 0
#define OBSW_ADD_PLOC_MPSOC 0
#define OBSW_ADD_SUN_SENSORS 1
#define OBSW_ADD_SUS_BOARD_ASS 1
#define OBSW_ADD_ACS_BOARD 1
#define OBSW_ADD_ACS_HANDLERS 1
#define OBSW_ADD_RW 0
#define OBSW_ADD_RTD_DEVICES 1
#define OBSW_ADD_TMP_DEVICES 0
#define OBSW_ADD_RAD_SENSORS 1
#define OBSW_ADD_PL_PCDU 1
#define OBSW_ADD_SYRLINKS 0
#define OBSW_ENABLE_SYRLINKS_TRANSMIT_TIMEOUT 0
#define OBSW_STAR_TRACKER_GROUND_CONFIG 1
#endif // XIPHOS_Q7S
// This is a really tricky switch.. It initializes the PCDU switches to their default states
// at powerup. I think it would be better
// to leave it off for now. It makes testing a lot more difficult and it might mess with
// something the operators might want to do by giving the software too much intelligence
// at the wrong place. The system component might command all the Switches accordingly anyway
#define OBSW_INITIALIZE_SWITCHES 0
#define OBSW_ENABLE_PERIODIC_HK 0
#ifdef TE0720_1CFA
#define OBSW_USE_CCSDS_IP_CORE 0
// Set to 1 if all telemetry should be sent to the PTME IP Core
#define OBSW_TM_TO_PTME 0
// Set to 1 if telecommands are received via the PDEC IP Core
#define OBSW_TC_FROM_PDEC 0
#define OBSW_ENABLE_TIMERS 1
#define OBSW_ADD_MGT 0
#define OBSW_ADD_BPX_BATTERY_HANDLER 0
#define OBSW_ADD_STAR_TRACKER 0
#define OBSW_ADD_PLOC_SUPERVISOR 0
#define OBSW_ADD_PLOC_MPSOC 1
#define OBSW_ADD_SUN_SENSORS 0
#define OBSW_ADD_ACS_BOARD 1
#define OBSW_ADD_ACS_HANDLERS 0
#define OBSW_ADD_RW 0
#define OBSW_ADD_RTD_DEVICES 0
#define OBSW_ADD_TMP_DEVICES 0
#define OBSW_ADD_RAD_SENSORS 0
#define OBSW_ADD_PL_PCDU 0
#define OBSW_ADD_SYRLINKS 0
#define OBSW_ENABLE_SYRLINKS_TRANSMIT_TIMEOUT 0
#define OBSW_SYRLINKS_SIMULATED 1
#define OBSW_STAR_TRACKER_GROUND_CONFIG 1
#define OBSW_ENABLE_PERIODIC_HK 0
#define OBSW_PRINT_CORE_HK 0
#define OBSW_INITIALIZE_SWITCHES 0
#endif
/*******************************************************************/
/** All of the following flags should be disabled for mission code */
/*******************************************************************/
// Can be used to switch device to NORMAL mode immediately
#define OBSW_SWITCH_TO_NORMAL_MODE_AFTER_STARTUP 1
#define OBSW_PRINT_MISSED_DEADLINES 1
#define OBSW_SYRLINKS_SIMULATED 1
#define OBSW_ADD_TEST_CODE 0
#define OBSW_ADD_TEST_TASK 0
#define OBSW_ADD_TEST_PST 0
// If this is enabled, all other SPI code should be disabled
#define OBSW_ADD_SPI_TEST_CODE 0
// If this is enabled, all other I2C code should be disabled
#define OBSW_ADD_I2C_TEST_CODE 0
#define OBSW_ADD_UART_TEST_CODE 0
#define OBSW_TEST_ACS 0
#define OBSW_DEBUG_ACS 0
#define OBSW_TEST_SUS 0
#define OBSW_DEBUG_SUS 0
#define OBSW_TEST_RTD 0
#define OBSW_DEBUG_RTD 0
#define OBSW_TEST_RAD_SENSOR 0
#define OBSW_DEBUG_RAD_SENSOR 0
#define OBSW_TEST_PL_PCDU 0
#define OBSW_DEBUG_PL_PCDU 0
#define OBSW_TEST_BPX_BATT 0
#define OBSW_DEBUG_BPX_BATT 0
#define OBSW_TEST_LIBGPIOD 0
#define OBSW_TEST_PLOC_HANDLER 0
#define OBSW_TEST_CCSDS_BRIDGE 0
#define OBSW_TEST_CCSDS_PTME 0
#define OBSW_TEST_TE7020_HEATER 0
#define OBSW_TEST_GPIO_OPEN_BY_LABEL 0
#define OBSW_TEST_GPIO_OPEN_BY_LINE_NAME 0
#define OBSW_DEBUG_P60DOCK 0
#define OBSW_PRINT_CORE_HK 0
#define OBSW_DEBUG_PDU1 0
#define OBSW_DEBUG_PDU2 0
#define OBSW_DEBUG_GPS 0
#define OBSW_DEBUG_ACU 0
#define OBSW_DEBUG_SYRLINKS 0
#define OBSW_DEBUG_IMTQ 0
#define OBSW_DEBUG_RW 0
#define OBSW_DEBUG_PDEC_HANDLER 0
#ifdef TE0720_1CFA
#define OBSW_DEBUG_PLOC_SUPERVISOR 1
#define OBSW_DEBUG_PLOC_MPSOC 1
#else
#define OBSW_DEBUG_PLOC_SUPERVISOR 0
#define OBSW_DEBUG_PLOC_MPSOC 0
#endif
#ifdef EGSE
#define OBSW_DEBUG_STARTRACKER 1
#else
#define OBSW_DEBUG_STARTRACKER 0
#endif
#ifdef RASPBERRY_PI
#define OBSW_TC_FROM_PDEC 0
#define OBSW_ENABLE_TIMERS 1
#define OBSW_ADD_STAR_TRACKER 0
#define OBSW_ADD_PLOC_SUPERVISOR 0
#define OBSW_ADD_PLOC_MPSOC 0
#define OBSW_ADD_SUN_SENSORS 0
#define OBSW_ADD_MGT 0
#define OBSW_ADD_ACS_BOARD 0
#define OBSW_ADD_ACS_HANDLERS 0
#define OBSW_ADD_GPS_0 0
#define OBSW_ADD_GPS_1 0
#define OBSW_ADD_RW 0
#define OBSW_ADD_BPX_BATTERY_HANDLER 0
#define OBSW_ADD_RTD_DEVICES 0
#define OBSW_ADD_PL_PCDU 0
#define OBSW_ADD_TMP_DEVICES 0
#define OBSW_ADD_RAD_SENSORS 0
#define OBSW_ADD_SYRLINKS 0
#define OBSW_STAR_TRACKER_GROUND_CONFIG 1
#endif // RASPBERRY_PI
#define TCP_SERVER_WIRETAPPING 0
/*******************************************************************/
/** CMake Defines */
/*******************************************************************/
#cmakedefine EIVE_BUILD_GPSD_GPS_HANDLER
#ifdef RASPBERRY_PI
#include "rpiConfig.h"
#elif defined(XIPHOS_Q7S)
#include "q7sConfig.h"
#endif
#ifdef __cplusplus
#include "objects/systemObjectList.h"
#include "events/subsystemIdRanges.h"
#include "returnvalues/classIds.h"
#endif
#endif /* FSFWCONFIG_OBSWCONFIG_H_ */

View File

@ -24,18 +24,18 @@ enum logicalAddresses : address_t {
RAD_SENSOR = objects::RAD_SENSOR,
SUS_0 = objects::SUS_0,
SUS_1 = objects::SUS_1,
SUS_2 = objects::SUS_2,
SUS_3 = objects::SUS_3,
SUS_4 = objects::SUS_4,
SUS_5 = objects::SUS_5,
SUS_6 = objects::SUS_6,
SUS_7 = objects::SUS_7,
SUS_8 = objects::SUS_8,
SUS_9 = objects::SUS_9,
SUS_10 = objects::SUS_10,
SUS_11 = objects::SUS_11,
SUS_0 = objects::SUS_0_N_LOC_XFYFZM_PT_XF,
SUS_1 = objects::SUS_1_N_LOC_XBYFZM_PT_XB,
SUS_2 = objects::SUS_2_N_LOC_XFYBZB_PT_YB,
SUS_3 = objects::SUS_3_N_LOC_XFYBZF_PT_YF,
SUS_4 = objects::SUS_4_N_LOC_XMYFZF_PT_ZF,
SUS_5 = objects::SUS_5_N_LOC_XFYMZB_PT_ZB,
SUS_6 = objects::SUS_6_R_LOC_XFYBZM_PT_XF,
SUS_7 = objects::SUS_7_R_LOC_XBYBZM_PT_XB,
SUS_8 = objects::SUS_8_R_LOC_XBYBZB_PT_YB,
SUS_9 = objects::SUS_9_R_LOC_XBYBZB_PT_YF,
SUS_10 = objects::SUS_10_N_LOC_XMYBZF_PT_ZF,
SUS_11 = objects::SUS_11_R_LOC_XBYMZB_PT_ZB,
/* Dummy and Test Addresses */
DUMMY_ECHO = 129,

View File

@ -13,7 +13,7 @@
namespace SUBSYSTEM_ID {
enum : uint8_t {
SUBSYSTEM_ID_START = COMMON_SUBSYSTEM_ID_END,
CORE = 136,
CORE = 137,
};
}

View File

@ -1,7 +1,7 @@
/**
* @brief Auto-generated event translation file. Contains 186 translations.
* @brief Auto-generated event translation file. Contains 207 translations.
* @details
* Generated on: 2022-04-08 14:13:35
* Generated on: 2022-05-25 18:14:41
*/
#include "translateEvents.h"
@ -82,16 +82,21 @@ const char *BIT_LOCK_LOST_STRING = "BIT_LOCK_LOST";
const char *FRAME_PROCESSING_FAILED_STRING = "FRAME_PROCESSING_FAILED";
const char *CLOCK_SET_STRING = "CLOCK_SET";
const char *CLOCK_SET_FAILURE_STRING = "CLOCK_SET_FAILURE";
const char *TC_DELETION_FAILED_STRING = "TC_DELETION_FAILED";
const char *TEST_STRING = "TEST";
const char *CHANGE_OF_SETUP_PARAMETER_STRING = "CHANGE_OF_SETUP_PARAMETER";
const char *SWITCH_CMD_SENT_STRING = "SWITCH_CMD_SENT";
const char *SWITCH_HAS_CHANGED_STRING = "SWITCH_HAS_CHANGED";
const char *SWITCHING_Q7S_DENIED_STRING = "SWITCHING_Q7S_DENIED";
const char *FDIR_REACTION_IGNORED_STRING = "FDIR_REACTION_IGNORED";
const char *GPIO_PULL_HIGH_FAILED_STRING = "GPIO_PULL_HIGH_FAILED";
const char *GPIO_PULL_LOW_FAILED_STRING = "GPIO_PULL_LOW_FAILED";
const char *HEATER_WENT_ON_STRING = "HEATER_WENT_ON";
const char *HEATER_WENT_OFF_STRING = "HEATER_WENT_OFF";
const char *SWITCH_ALREADY_ON_STRING = "SWITCH_ALREADY_ON";
const char *SWITCH_ALREADY_OFF_STRING = "SWITCH_ALREADY_OFF";
const char *MAIN_SWITCH_TIMEOUT_STRING = "MAIN_SWITCH_TIMEOUT";
const char *FAULTY_HEATER_WAS_ON_STRING = "FAULTY_HEATER_WAS_ON";
const char *MAIN_SWITCH_ON_TIMEOUT_STRING = "MAIN_SWITCH_ON_TIMEOUT";
const char *MAIN_SWITCH_OFF_TIMEOUT_STRING = "MAIN_SWITCH_OFF_TIMEOUT";
const char *DEPLOYMENT_FAILED_STRING = "DEPLOYMENT_FAILED";
@ -101,7 +106,7 @@ const char *MEMORY_READ_RPT_CRC_FAILURE_STRING = "MEMORY_READ_RPT_CRC_FAILURE";
const char *ACK_FAILURE_STRING = "ACK_FAILURE";
const char *EXE_FAILURE_STRING = "EXE_FAILURE";
const char *MPSOC_HANDLER_CRC_FAILURE_STRING = "MPSOC_HANDLER_CRC_FAILURE";
const char *MPSOC_HANDLER_SEQ_CNT_MISMATCH_STRING = "MPSOC_HANDLER_SEQ_CNT_MISMATCH";
const char *MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH_STRING = "MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH";
const char *MPSOC_SHUTDOWN_FAILED_STRING = "MPSOC_SHUTDOWN_FAILED";
const char *SELF_TEST_I2C_FAILURE_STRING = "SELF_TEST_I2C_FAILURE";
const char *SELF_TEST_SPI_FAILURE_STRING = "SELF_TEST_SPI_FAILURE";
@ -112,20 +117,16 @@ const char *SELF_TEST_MTM_RANGE_FAILURE_STRING = "SELF_TEST_MTM_RANGE_FAILURE";
const char *SELF_TEST_COIL_CURRENT_FAILURE_STRING = "SELF_TEST_COIL_CURRENT_FAILURE";
const char *INVALID_ERROR_BYTE_STRING = "INVALID_ERROR_BYTE";
const char *ERROR_STATE_STRING = "ERROR_STATE";
const char *RESET_OCCURED_STRING = "RESET_OCCURED";
const char *BOOTING_FIRMWARE_FAILED_STRING = "BOOTING_FIRMWARE_FAILED";
const char *BOOTING_BOOTLOADER_FAILED_STRING = "BOOTING_BOOTLOADER_FAILED";
const char *SUPV_MEMORY_READ_RPT_CRC_FAILURE_STRING = "SUPV_MEMORY_READ_RPT_CRC_FAILURE";
const char *SUPV_ACK_FAILURE_STRING = "SUPV_ACK_FAILURE";
const char *SUPV_EXE_FAILURE_STRING = "SUPV_EXE_FAILURE";
const char *SUPV_CRC_FAILURE_EVENT_STRING = "SUPV_CRC_FAILURE_EVENT";
const char *SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING = "SUPV_MPSOC_SHUWDOWN_BUILD_FAILED";
const char *SANITIZATION_FAILED_STRING = "SANITIZATION_FAILED";
const char *MOUNTED_SD_CARD_STRING = "MOUNTED_SD_CARD";
const char *UPDATE_FILE_NOT_EXISTS_STRING = "UPDATE_FILE_NOT_EXISTS";
const char *ACTION_COMMANDING_FAILED_STRING = "ACTION_COMMANDING_FAILED";
const char *UPDATE_AVAILABLE_FAILED_STRING = "UPDATE_AVAILABLE_FAILED";
const char *UPDATE_TRANSFER_FAILED_STRING = "UPDATE_TRANSFER_FAILED";
const char *UPDATE_VERIFY_FAILED_STRING = "UPDATE_VERIFY_FAILED";
const char *UPDATE_FINISHED_STRING = "UPDATE_FINISHED";
const char *SEND_MRAM_DUMP_FAILED_STRING = "SEND_MRAM_DUMP_FAILED";
const char *MRAM_DUMP_FAILED_STRING = "MRAM_DUMP_FAILED";
const char *MRAM_DUMP_FINISHED_STRING = "MRAM_DUMP_FINISHED";
@ -152,15 +153,15 @@ const char *STR_HELPER_SENDING_PACKET_FAILED_STRING = "STR_HELPER_SENDING_PACKET
const char *STR_HELPER_REQUESTING_MSG_FAILED_STRING = "STR_HELPER_REQUESTING_MSG_FAILED";
const char *MPSOC_FLASH_WRITE_FAILED_STRING = "MPSOC_FLASH_WRITE_FAILED";
const char *MPSOC_FLASH_WRITE_SUCCESSFUL_STRING = "MPSOC_FLASH_WRITE_SUCCESSFUL";
const char *SENDING_COMMAND_FAILED_STRING = "SENDING_COMMAND_FAILED";
const char *MPSOC_SENDING_COMMAND_FAILED_STRING = "MPSOC_SENDING_COMMAND_FAILED";
const char *MPSOC_HELPER_REQUESTING_REPLY_FAILED_STRING = "MPSOC_HELPER_REQUESTING_REPLY_FAILED";
const char *MPSOC_HELPER_READING_REPLY_FAILED_STRING = "MPSOC_HELPER_READING_REPLY_FAILED";
const char *MISSING_ACK_STRING = "MISSING_ACK";
const char *MISSING_EXE_STRING = "MISSING_EXE";
const char *ACK_FAILURE_REPORT_STRING = "ACK_FAILURE_REPORT";
const char *EXE_FAILURE_REPORT_STRING = "EXE_FAILURE_REPORT";
const char *ACK_INVALID_APID_STRING = "ACK_INVALID_APID";
const char *EXE_INVALID_APID_STRING = "EXE_INVALID_APID";
const char *MPSOC_MISSING_ACK_STRING = "MPSOC_MISSING_ACK";
const char *MPSOC_MISSING_EXE_STRING = "MPSOC_MISSING_EXE";
const char *MPSOC_ACK_FAILURE_REPORT_STRING = "MPSOC_ACK_FAILURE_REPORT";
const char *MPSOC_EXE_FAILURE_REPORT_STRING = "MPSOC_EXE_FAILURE_REPORT";
const char *MPSOC_ACK_INVALID_APID_STRING = "MPSOC_ACK_INVALID_APID";
const char *MPSOC_EXE_INVALID_APID_STRING = "MPSOC_EXE_INVALID_APID";
const char *MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING = "MPSOC_HELPER_SEQ_CNT_MISMATCH";
const char *TRANSITION_BACK_TO_OFF_STRING = "TRANSITION_BACK_TO_OFF";
const char *NEG_V_OUT_OF_BOUNDS_STRING = "NEG_V_OUT_OF_BOUNDS";
@ -183,6 +184,26 @@ const char *GPS_FIX_CHANGE_STRING = "GPS_FIX_CHANGE";
const char *P60_BOOT_COUNT_STRING = "P60_BOOT_COUNT";
const char *BATT_MODE_STRING = "BATT_MODE";
const char *BATT_MODE_CHANGED_STRING = "BATT_MODE_CHANGED";
const char *SUPV_UPDATE_FAILED_STRING = "SUPV_UPDATE_FAILED";
const char *SUPV_UPDATE_SUCCESSFUL_STRING = "SUPV_UPDATE_SUCCESSFUL";
const char *SUPV_CONTINUE_UPDATE_FAILED_STRING = "SUPV_CONTINUE_UPDATE_FAILED";
const char *SUPV_CONTINUE_UPDATE_SUCCESSFUL_STRING = "SUPV_CONTINUE_UPDATE_SUCCESSFUL";
const char *TERMINATED_UPDATE_PROCEDURE_STRING = "TERMINATED_UPDATE_PROCEDURE";
const char *SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL_STRING = "SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL";
const char *SUPV_EVENT_BUFFER_REQUEST_FAILED_STRING = "SUPV_EVENT_BUFFER_REQUEST_FAILED";
const char *SUPV_EVENT_BUFFER_REQUEST_TERMINATED_STRING = "SUPV_EVENT_BUFFER_REQUEST_TERMINATED";
const char *SUPV_SENDING_COMMAND_FAILED_STRING = "SUPV_SENDING_COMMAND_FAILED";
const char *SUPV_HELPER_REQUESTING_REPLY_FAILED_STRING = "SUPV_HELPER_REQUESTING_REPLY_FAILED";
const char *SUPV_HELPER_READING_REPLY_FAILED_STRING = "SUPV_HELPER_READING_REPLY_FAILED";
const char *SUPV_MISSING_ACK_STRING = "SUPV_MISSING_ACK";
const char *SUPV_MISSING_EXE_STRING = "SUPV_MISSING_EXE";
const char *SUPV_ACK_FAILURE_REPORT_STRING = "SUPV_ACK_FAILURE_REPORT";
const char *SUPV_EXE_FAILURE_REPORT_STRING = "SUPV_EXE_FAILURE_REPORT";
const char *SUPV_ACK_INVALID_APID_STRING = "SUPV_ACK_INVALID_APID";
const char *SUPV_EXE_INVALID_APID_STRING = "SUPV_EXE_INVALID_APID";
const char *ACK_RECEPTION_FAILURE_STRING = "ACK_RECEPTION_FAILURE";
const char *EXE_RECEPTION_FAILURE_STRING = "EXE_RECEPTION_FAILURE";
const char *WRITE_MEMORY_FAILED_STRING = "WRITE_MEMORY_FAILED";
const char *ALLOC_FAILURE_STRING = "ALLOC_FAILURE";
const char *REBOOT_SW_STRING = "REBOOT_SW";
const char *REBOOT_MECHANISM_TRIGGERED_STRING = "REBOOT_MECHANISM_TRIGGERED";
@ -344,6 +365,8 @@ const char *translateEvents(Event event) {
return CLOCK_SET_STRING;
case (8901):
return CLOCK_SET_FAILURE_STRING;
case (9100):
return TC_DELETION_FAILED_STRING;
case (9700):
return TEST_STRING;
case (10600):
@ -354,16 +377,24 @@ const char *translateEvents(Event event) {
return SWITCH_HAS_CHANGED_STRING;
case (11302):
return SWITCHING_Q7S_DENIED_STRING;
case (11303):
return FDIR_REACTION_IGNORED_STRING;
case (11400):
return GPIO_PULL_HIGH_FAILED_STRING;
case (11401):
return GPIO_PULL_LOW_FAILED_STRING;
case (11402):
return SWITCH_ALREADY_ON_STRING;
return HEATER_WENT_ON_STRING;
case (11403):
return SWITCH_ALREADY_OFF_STRING;
return HEATER_WENT_OFF_STRING;
case (11404):
return SWITCH_ALREADY_ON_STRING;
case (11405):
return SWITCH_ALREADY_OFF_STRING;
case (11406):
return MAIN_SWITCH_TIMEOUT_STRING;
case (11407):
return FAULTY_HEATER_WAS_ON_STRING;
case (11500):
return MAIN_SWITCH_ON_TIMEOUT_STRING;
case (11501):
@ -383,7 +414,7 @@ const char *translateEvents(Event event) {
case (11604):
return MPSOC_HANDLER_CRC_FAILURE_STRING;
case (11605):
return MPSOC_HANDLER_SEQ_CNT_MISMATCH_STRING;
return MPSOC_HANDLER_SEQUENCE_COUNT_MISMATCH_STRING;
case (11606):
return MPSOC_SHUTDOWN_FAILED_STRING;
case (11701):
@ -404,6 +435,8 @@ const char *translateEvents(Event event) {
return INVALID_ERROR_BYTE_STRING;
case (11801):
return ERROR_STATE_STRING;
case (11802):
return RESET_OCCURED_STRING;
case (11901):
return BOOTING_FIRMWARE_FAILED_STRING;
case (11902):
@ -416,22 +449,12 @@ const char *translateEvents(Event event) {
return SUPV_EXE_FAILURE_STRING;
case (12004):
return SUPV_CRC_FAILURE_EVENT_STRING;
case (12005):
return SUPV_MPSOC_SHUWDOWN_BUILD_FAILED_STRING;
case (12100):
return SANITIZATION_FAILED_STRING;
case (12101):
return MOUNTED_SD_CARD_STRING;
case (12200):
return UPDATE_FILE_NOT_EXISTS_STRING;
case (12201):
return ACTION_COMMANDING_FAILED_STRING;
case (12202):
return UPDATE_AVAILABLE_FAILED_STRING;
case (12203):
return UPDATE_TRANSFER_FAILED_STRING;
case (12204):
return UPDATE_VERIFY_FAILED_STRING;
case (12205):
return UPDATE_FINISHED_STRING;
case (12300):
return SEND_MRAM_DUMP_FAILED_STRING;
case (12301):
@ -485,23 +508,23 @@ const char *translateEvents(Event event) {
case (12601):
return MPSOC_FLASH_WRITE_SUCCESSFUL_STRING;
case (12602):
return SENDING_COMMAND_FAILED_STRING;
return MPSOC_SENDING_COMMAND_FAILED_STRING;
case (12603):
return MPSOC_HELPER_REQUESTING_REPLY_FAILED_STRING;
case (12604):
return MPSOC_HELPER_READING_REPLY_FAILED_STRING;
case (12605):
return MISSING_ACK_STRING;
return MPSOC_MISSING_ACK_STRING;
case (12606):
return MISSING_EXE_STRING;
return MPSOC_MISSING_EXE_STRING;
case (12607):
return ACK_FAILURE_REPORT_STRING;
return MPSOC_ACK_FAILURE_REPORT_STRING;
case (12608):
return EXE_FAILURE_REPORT_STRING;
return MPSOC_EXE_FAILURE_REPORT_STRING;
case (12609):
return ACK_INVALID_APID_STRING;
return MPSOC_ACK_INVALID_APID_STRING;
case (12610):
return EXE_INVALID_APID_STRING;
return MPSOC_EXE_INVALID_APID_STRING;
case (12611):
return MPSOC_HELPER_SEQ_CNT_MISMATCH_STRING;
case (12700):
@ -547,12 +570,52 @@ const char *translateEvents(Event event) {
case (13202):
return BATT_MODE_CHANGED_STRING;
case (13600):
return ALLOC_FAILURE_STRING;
return SUPV_UPDATE_FAILED_STRING;
case (13601):
return REBOOT_SW_STRING;
return SUPV_UPDATE_SUCCESSFUL_STRING;
case (13602):
return REBOOT_MECHANISM_TRIGGERED_STRING;
return SUPV_CONTINUE_UPDATE_FAILED_STRING;
case (13603):
return SUPV_CONTINUE_UPDATE_SUCCESSFUL_STRING;
case (13604):
return TERMINATED_UPDATE_PROCEDURE_STRING;
case (13605):
return SUPV_EVENT_BUFFER_REQUEST_SUCCESSFUL_STRING;
case (13606):
return SUPV_EVENT_BUFFER_REQUEST_FAILED_STRING;
case (13607):
return SUPV_EVENT_BUFFER_REQUEST_TERMINATED_STRING;
case (13608):
return SUPV_SENDING_COMMAND_FAILED_STRING;
case (13609):
return SUPV_HELPER_REQUESTING_REPLY_FAILED_STRING;
case (13610):
return SUPV_HELPER_READING_REPLY_FAILED_STRING;
case (13611):
return SUPV_MISSING_ACK_STRING;
case (13612):
return SUPV_MISSING_EXE_STRING;
case (13613):
return SUPV_ACK_FAILURE_REPORT_STRING;
case (13614):
return SUPV_EXE_FAILURE_REPORT_STRING;
case (13615):
return SUPV_ACK_INVALID_APID_STRING;
case (13616):
return SUPV_EXE_INVALID_APID_STRING;
case (13617):
return ACK_RECEPTION_FAILURE_STRING;
case (13618):
return EXE_RECEPTION_FAILURE_STRING;
case (13619):
return WRITE_MEMORY_FAILED_STRING;
case (13700):
return ALLOC_FAILURE_STRING;
case (13701):
return REBOOT_SW_STRING;
case (13702):
return REBOOT_MECHANISM_TRIGGERED_STRING;
case (13703):
return REBOOT_HW_STRING;
default:
return "UNKNOWN_EVENT";

View File

@ -47,7 +47,7 @@ enum sourceObjects : uint32_t {
CSP_COM_IF = 0x49050001,
I2C_COM_IF = 0x49040002,
UART_COM_IF = 0x49030003,
SPI_COM_IF = 0x49020004,
SPI_MAIN_COM_IF = 0x49020004,
GPIO_IF = 0x49010005,
SCEX_UART_READER = 0x49010006,
@ -57,6 +57,8 @@ enum sourceObjects : uint32_t {
SYRLINKS_HK_HANDLER = 0x445300A3,
HEATER_HANDLER = 0x444100A4,
RAD_SENSOR = 0x443200A5,
SPI_RW_COM_IF = 0x49020005,
SPI_RTD_COM_IF = 0x49020006,
/* 0x54 ('T') for test handlers */
TEST_TASK = 0x54694269,

View File

@ -1,8 +1,8 @@
/**
* @brief Auto-generated object translation file.
* @details
* Contains 117 translations.
* Generated on: 2022-04-08 14:13:35
* Contains 131 translations.
* Generated on: 2022-05-25 18:14:41
*/
#include "translateObjects.h"
@ -12,18 +12,18 @@ const char *ACS_CONTROLLER_STRING = "ACS_CONTROLLER";
const char *THERMAL_CONTROLLER_STRING = "THERMAL_CONTROLLER";
const char *MGM_0_LIS3_HANDLER_STRING = "MGM_0_LIS3_HANDLER";
const char *GYRO_0_ADIS_HANDLER_STRING = "GYRO_0_ADIS_HANDLER";
const char *SUS_0_STRING = "SUS_0";
const char *SUS_1_STRING = "SUS_1";
const char *SUS_2_STRING = "SUS_2";
const char *SUS_3_STRING = "SUS_3";
const char *SUS_4_STRING = "SUS_4";
const char *SUS_5_STRING = "SUS_5";
const char *SUS_6_STRING = "SUS_6";
const char *SUS_7_STRING = "SUS_7";
const char *SUS_8_STRING = "SUS_8";
const char *SUS_9_STRING = "SUS_9";
const char *SUS_10_STRING = "SUS_10";
const char *SUS_11_STRING = "SUS_11";
const char *SUS_0_N_LOC_XFYFZM_PT_XF_STRING = "SUS_0_N_LOC_XFYFZM_PT_XF";
const char *SUS_1_N_LOC_XBYFZM_PT_XB_STRING = "SUS_1_N_LOC_XBYFZM_PT_XB";
const char *SUS_2_N_LOC_XFYBZB_PT_YB_STRING = "SUS_2_N_LOC_XFYBZB_PT_YB";
const char *SUS_3_N_LOC_XFYBZF_PT_YF_STRING = "SUS_3_N_LOC_XFYBZF_PT_YF";
const char *SUS_4_N_LOC_XMYFZF_PT_ZF_STRING = "SUS_4_N_LOC_XMYFZF_PT_ZF";
const char *SUS_5_N_LOC_XFYMZB_PT_ZB_STRING = "SUS_5_N_LOC_XFYMZB_PT_ZB";
const char *SUS_6_R_LOC_XFYBZM_PT_XF_STRING = "SUS_6_R_LOC_XFYBZM_PT_XF";
const char *SUS_7_R_LOC_XBYBZM_PT_XB_STRING = "SUS_7_R_LOC_XBYBZM_PT_XB";
const char *SUS_8_R_LOC_XBYBZB_PT_YB_STRING = "SUS_8_R_LOC_XBYBZB_PT_YB";
const char *SUS_9_R_LOC_XBYBZB_PT_YF_STRING = "SUS_9_R_LOC_XBYBZB_PT_YF";
const char *SUS_10_N_LOC_XMYBZF_PT_ZF_STRING = "SUS_10_N_LOC_XMYBZF_PT_ZF";
const char *SUS_11_R_LOC_XBYMZB_PT_ZB_STRING = "SUS_11_R_LOC_XBYMZB_PT_ZB";
const char *RW1_STRING = "RW1";
const char *MGM_1_RM3100_HANDLER_STRING = "MGM_1_RM3100_HANDLER";
const char *GYRO_1_L3G_HANDLER_STRING = "GYRO_1_L3G_HANDLER";
@ -49,6 +49,8 @@ const char *PLOC_UPDATER_STRING = "PLOC_UPDATER";
const char *PLOC_MEMORY_DUMPER_STRING = "PLOC_MEMORY_DUMPER";
const char *STR_HELPER_STRING = "STR_HELPER";
const char *PLOC_MPSOC_HELPER_STRING = "PLOC_MPSOC_HELPER";
const char *AXI_PTME_CONFIG_STRING = "AXI_PTME_CONFIG";
const char *PTME_CONFIG_STRING = "PTME_CONFIG";
const char *PLOC_MPSOC_HANDLER_STRING = "PLOC_MPSOC_HANDLER";
const char *PLOC_SUPERVISOR_HANDLER_STRING = "PLOC_SUPERVISOR_HANDLER";
const char *PLOC_SUPERVISOR_HELPER_STRING = "PLOC_SUPERVISOR_HELPER";
@ -56,26 +58,28 @@ const char *SOLAR_ARRAY_DEPL_HANDLER_STRING = "SOLAR_ARRAY_DEPL_HANDLER";
const char *HEATER_HANDLER_STRING = "HEATER_HANDLER";
const char *TMP1075_HANDLER_1_STRING = "TMP1075_HANDLER_1";
const char *TMP1075_HANDLER_2_STRING = "TMP1075_HANDLER_2";
const char *RTD_IC_3_STRING = "RTD_IC_3";
const char *RTD_IC_4_STRING = "RTD_IC_4";
const char *RTD_IC_5_STRING = "RTD_IC_5";
const char *RTD_IC_6_STRING = "RTD_IC_6";
const char *RTD_IC_7_STRING = "RTD_IC_7";
const char *RTD_IC_8_STRING = "RTD_IC_8";
const char *RTD_IC_9_STRING = "RTD_IC_9";
const char *RTD_IC_10_STRING = "RTD_IC_10";
const char *RTD_IC_11_STRING = "RTD_IC_11";
const char *RTD_IC_12_STRING = "RTD_IC_12";
const char *RTD_IC_13_STRING = "RTD_IC_13";
const char *RTD_IC_14_STRING = "RTD_IC_14";
const char *RTD_IC_15_STRING = "RTD_IC_15";
const char *RTD_IC_16_STRING = "RTD_IC_16";
const char *RTD_IC_17_STRING = "RTD_IC_17";
const char *RTD_IC_18_STRING = "RTD_IC_18";
const char *RTD_0_IC3_PLOC_HEATSPREADER_STRING = "RTD_0_IC3_PLOC_HEATSPREADER";
const char *RTD_1_IC4_PLOC_MISSIONBOARD_STRING = "RTD_1_IC4_PLOC_MISSIONBOARD";
const char *RTD_2_IC5_4K_CAMERA_STRING = "RTD_2_IC5_4K_CAMERA";
const char *RTD_3_IC6_DAC_HEATSPREADER_STRING = "RTD_3_IC6_DAC_HEATSPREADER";
const char *RTD_4_IC7_STARTRACKER_STRING = "RTD_4_IC7_STARTRACKER";
const char *RTD_5_IC8_RW1_MX_MY_STRING = "RTD_5_IC8_RW1_MX_MY";
const char *RTD_6_IC9_DRO_STRING = "RTD_6_IC9_DRO";
const char *RTD_7_IC10_SCEX_STRING = "RTD_7_IC10_SCEX";
const char *RTD_8_IC11_X8_STRING = "RTD_8_IC11_X8";
const char *RTD_9_IC12_HPA_STRING = "RTD_9_IC12_HPA";
const char *RTD_10_IC13_PL_TX_STRING = "RTD_10_IC13_PL_TX";
const char *RTD_11_IC14_MPA_STRING = "RTD_11_IC14_MPA";
const char *RTD_12_IC15_ACU_STRING = "RTD_12_IC15_ACU";
const char *RTD_13_IC16_PLPCDU_HEATSPREADER_STRING = "RTD_13_IC16_PLPCDU_HEATSPREADER";
const char *RTD_14_IC17_TCS_BOARD_STRING = "RTD_14_IC17_TCS_BOARD";
const char *RTD_15_IC18_IMTQ_STRING = "RTD_15_IC18_IMTQ";
const char *SYRLINKS_HK_HANDLER_STRING = "SYRLINKS_HK_HANDLER";
const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF";
const char *GPIO_IF_STRING = "GPIO_IF";
const char *SPI_COM_IF_STRING = "SPI_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 *SPI_RTD_COM_IF_STRING = "SPI_RTD_COM_IF";
const char *UART_COM_IF_STRING = "UART_COM_IF";
const char *I2C_COM_IF_STRING = "I2C_COM_IF";
const char *CSP_COM_IF_STRING = "CSP_COM_IF";
@ -96,6 +100,7 @@ const char *PUS_SERVICE_3_HOUSEKEEPING_STRING = "PUS_SERVICE_3_HOUSEKEEPING";
const char *PUS_SERVICE_5_EVENT_REPORTING_STRING = "PUS_SERVICE_5_EVENT_REPORTING";
const char *PUS_SERVICE_8_FUNCTION_MGMT_STRING = "PUS_SERVICE_8_FUNCTION_MGMT";
const char *PUS_SERVICE_9_TIME_MGMT_STRING = "PUS_SERVICE_9_TIME_MGMT";
const char *PUS_SERVICE_11_TC_SCHEDULER_STRING = "PUS_SERVICE_11_TC_SCHEDULER";
const char *PUS_SERVICE_17_TEST_STRING = "PUS_SERVICE_17_TEST";
const char *PUS_SERVICE_20_PARAMETERS_STRING = "PUS_SERVICE_20_PARAMETERS";
const char *PUS_SERVICE_200_MODE_MGMT_STRING = "PUS_SERVICE_200_MODE_MGMT";
@ -117,9 +122,18 @@ const char *DUMMY_HANDLER_STRING = "DUMMY_HANDLER";
const char *DUMMY_INTERFACE_STRING = "DUMMY_INTERFACE";
const char *LIBGPIOD_TEST_STRING = "LIBGPIOD_TEST";
const char *TEST_TASK_STRING = "TEST_TASK";
const char *HEATER_0_PLOC_PROC_BRD_STRING = "HEATER_0_PLOC_PROC_BRD";
const char *HEATER_1_PCDU_BRD_STRING = "HEATER_1_PCDU_BRD";
const char *HEATER_2_ACS_BRD_STRING = "HEATER_2_ACS_BRD";
const char *HEATER_3_OBC_BRD_STRING = "HEATER_3_OBC_BRD";
const char *HEATER_4_CAMERA_STRING = "HEATER_4_CAMERA";
const char *HEATER_5_STR_STRING = "HEATER_5_STR";
const char *HEATER_6_DRO_STRING = "HEATER_6_DRO";
const char *HEATER_7_HPA_STRING = "HEATER_7_HPA";
const char *ACS_BOARD_ASS_STRING = "ACS_BOARD_ASS";
const char *SUS_BOARD_ASS_STRING = "SUS_BOARD_ASS";
const char *TCS_BOARD_ASS_STRING = "TCS_BOARD_ASS";
const char *RW_ASS_STRING = "RW_ASS";
const char *TM_FUNNEL_STRING = "TM_FUNNEL";
const char *CCSDS_IP_CORE_BRIDGE_STRING = "CCSDS_IP_CORE_BRIDGE";
const char *NO_OBJECT_STRING = "NO_OBJECT";
@ -139,29 +153,29 @@ const char *translateObject(object_id_t object) {
case 0x44120010:
return GYRO_0_ADIS_HANDLER_STRING;
case 0x44120032:
return SUS_0_STRING;
return SUS_0_N_LOC_XFYFZM_PT_XF_STRING;
case 0x44120033:
return SUS_1_STRING;
return SUS_1_N_LOC_XBYFZM_PT_XB_STRING;
case 0x44120034:
return SUS_2_STRING;
return SUS_2_N_LOC_XFYBZB_PT_YB_STRING;
case 0x44120035:
return SUS_3_STRING;
return SUS_3_N_LOC_XFYBZF_PT_YF_STRING;
case 0x44120036:
return SUS_4_STRING;
return SUS_4_N_LOC_XMYFZF_PT_ZF_STRING;
case 0x44120037:
return SUS_5_STRING;
return SUS_5_N_LOC_XFYMZB_PT_ZB_STRING;
case 0x44120038:
return SUS_6_STRING;
return SUS_6_R_LOC_XFYBZM_PT_XF_STRING;
case 0x44120039:
return SUS_7_STRING;
return SUS_7_R_LOC_XBYBZM_PT_XB_STRING;
case 0x44120040:
return SUS_8_STRING;
return SUS_8_R_LOC_XBYBZB_PT_YB_STRING;
case 0x44120041:
return SUS_9_STRING;
return SUS_9_R_LOC_XBYBZB_PT_YF_STRING;
case 0x44120042:
return SUS_10_STRING;
return SUS_10_N_LOC_XMYBZF_PT_ZF_STRING;
case 0x44120043:
return SUS_11_STRING;
return SUS_11_R_LOC_XBYMZB_PT_ZB_STRING;
case 0x44120047:
return RW1_STRING;
case 0x44120107:
@ -212,6 +226,10 @@ const char *translateObject(object_id_t object) {
return STR_HELPER_STRING;
case 0x44330003:
return PLOC_MPSOC_HELPER_STRING;
case 0x44330004:
return AXI_PTME_CONFIG_STRING;
case 0x44330005:
return PTME_CONFIG_STRING;
case 0x44330015:
return PLOC_MPSOC_HANDLER_STRING;
case 0x44330016:
@ -227,37 +245,37 @@ const char *translateObject(object_id_t object) {
case 0x44420005:
return TMP1075_HANDLER_2_STRING;
case 0x44420016:
return RTD_IC_3_STRING;
return RTD_0_IC3_PLOC_HEATSPREADER_STRING;
case 0x44420017:
return RTD_IC_4_STRING;
return RTD_1_IC4_PLOC_MISSIONBOARD_STRING;
case 0x44420018:
return RTD_IC_5_STRING;
return RTD_2_IC5_4K_CAMERA_STRING;
case 0x44420019:
return RTD_IC_6_STRING;
return RTD_3_IC6_DAC_HEATSPREADER_STRING;
case 0x44420020:
return RTD_IC_7_STRING;
return RTD_4_IC7_STARTRACKER_STRING;
case 0x44420021:
return RTD_IC_8_STRING;
return RTD_5_IC8_RW1_MX_MY_STRING;
case 0x44420022:
return RTD_IC_9_STRING;
return RTD_6_IC9_DRO_STRING;
case 0x44420023:
return RTD_IC_10_STRING;
return RTD_7_IC10_SCEX_STRING;
case 0x44420024:
return RTD_IC_11_STRING;
return RTD_8_IC11_X8_STRING;
case 0x44420025:
return RTD_IC_12_STRING;
return RTD_9_IC12_HPA_STRING;
case 0x44420026:
return RTD_IC_13_STRING;
return RTD_10_IC13_PL_TX_STRING;
case 0x44420027:
return RTD_IC_14_STRING;
return RTD_11_IC14_MPA_STRING;
case 0x44420028:
return RTD_IC_15_STRING;
return RTD_12_IC15_ACU_STRING;
case 0x44420029:
return RTD_IC_16_STRING;
return RTD_13_IC16_PLPCDU_HEATSPREADER_STRING;
case 0x44420030:
return RTD_IC_17_STRING;
return RTD_14_IC17_TCS_BOARD_STRING;
case 0x44420031:
return RTD_IC_18_STRING;
return RTD_15_IC18_IMTQ_STRING;
case 0x445300A3:
return SYRLINKS_HK_HANDLER_STRING;
case 0x49000000:
@ -265,7 +283,11 @@ const char *translateObject(object_id_t object) {
case 0x49010005:
return GPIO_IF_STRING;
case 0x49020004:
return SPI_COM_IF_STRING;
return SPI_MAIN_COM_IF_STRING;
case 0x49020005:
return SPI_RW_COM_IF_STRING;
case 0x49020006:
return SPI_RTD_COM_IF_STRING;
case 0x49030003:
return UART_COM_IF_STRING;
case 0x49040002:
@ -306,6 +328,8 @@ const char *translateObject(object_id_t object) {
return PUS_SERVICE_8_FUNCTION_MGMT_STRING;
case 0x53000009:
return PUS_SERVICE_9_TIME_MGMT_STRING;
case 0x53000011:
return PUS_SERVICE_11_TC_SCHEDULER_STRING;
case 0x53000017:
return PUS_SERVICE_17_TEST_STRING;
case 0x53000020:
@ -348,12 +372,30 @@ const char *translateObject(object_id_t object) {
return LIBGPIOD_TEST_STRING;
case 0x54694269:
return TEST_TASK_STRING;
case 0x60000000:
return HEATER_0_PLOC_PROC_BRD_STRING;
case 0x60000001:
return HEATER_1_PCDU_BRD_STRING;
case 0x60000002:
return HEATER_2_ACS_BRD_STRING;
case 0x60000003:
return HEATER_3_OBC_BRD_STRING;
case 0x60000004:
return HEATER_4_CAMERA_STRING;
case 0x60000005:
return HEATER_5_STR_STRING;
case 0x60000006:
return HEATER_6_DRO_STRING;
case 0x60000007:
return HEATER_7_HPA_STRING;
case 0x73000001:
return ACS_BOARD_ASS_STRING;
case 0x73000002:
return SUS_BOARD_ASS_STRING;
case 0x73000003:
return TCS_BOARD_ASS_STRING;
case 0x73000004:
return RW_ASS_STRING;
case 0x73000100:
return TM_FUNNEL_STRING;
case 0x73500000:

View File

@ -5,6 +5,8 @@
#include <fsfw/serviceinterface/ServiceInterfaceStream.h>
#include <fsfw/tasks/FixedTimeslotTaskIF.h>
#include "mission/devices/devicedefinitions/Max31865Definitions.h"
#ifndef RPI_TEST_ADIS16507
#define RPI_TEST_ADIS16507 0
#endif
@ -29,138 +31,69 @@ ReturnValue_t pst::pstGpio(FixedTimeslotTaskIF *thisSequence) {
return HasReturnvaluesIF::RETURN_FAILED;
}
ReturnValue_t pst::pstSpiRw(FixedTimeslotTaskIF *thisSequence) {
uint32_t length = thisSequence->getPeriodMs();
static_cast<void>(length);
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.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW2, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW3, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW4, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW1, length * 0.8, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW2, length * 0.8, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW3, length * 0.8, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW4, length * 0.8, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW1, length * 0.8, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW2, length * 0.8, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW3, length * 0.8, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW4, length * 0.8, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW1, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RW2, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RW3, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RW4, length * 0.8, DeviceHandlerIF::GET_READ);
return thisSequence->checkSequence();
}
ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) {
uint32_t length = thisSequence->getPeriodMs();
static_cast<void>(length);
#if OBSW_ADD_PL_PCDU == 1
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::PLPCDU_HANDLER, length * 0, DeviceHandlerIF::GET_READ);
#endif
#if OBSW_ADD_TMP_DEVICES == 1
thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
#endif
#if OBSW_ADD_RTD_DEVICES == 1
thisSequence->addSlot(objects::RTD_IC_3, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_4, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_5, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_6, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_7, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_8, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_9, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_10, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_11, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_12, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_13, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_14, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_15, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_16, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_17, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RTD_IC_18, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
#endif /* OBSW_ADD_RTD_DEVICES */
#if OBSW_ADD_TMP_DEVICES == 1
thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::SEND_WRITE);
#endif
#if OBSW_ADD_RTD_DEVICES == 1
thisSequence->addSlot(objects::RTD_IC_3, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_4, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_5, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_6, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_7, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_8, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_9, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_10, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_11, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_12, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_13, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_14, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_15, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_16, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_17, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RTD_IC_18, length * 0.2, DeviceHandlerIF::SEND_WRITE);
#endif /* OBSW_ADD_RTD_DEVICES */
#if OBSW_ADD_TMP_DEVICES == 1
thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::GET_WRITE);
#endif
#if OBSW_ADD_RTD_DEVICES == 1
thisSequence->addSlot(objects::RTD_IC_3, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_4, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_5, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_6, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_7, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_8, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_9, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_10, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_11, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_12, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_13, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_14, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_15, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_16, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_17, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RTD_IC_18, length * 0.4, DeviceHandlerIF::GET_WRITE);
#endif /* OBSW_ADD_RTD_DEVICES */
#if OBSW_ADD_TMP_DEVICES == 1
thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::SEND_READ);
#endif
#if OBSW_ADD_RTD_DEVICES == 1
thisSequence->addSlot(objects::RTD_IC_3, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_4, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_5, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_6, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_7, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_8, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_9, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_10, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_11, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_12, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_13, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_14, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_15, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_16, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_17, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RTD_IC_18, length * 0.6, DeviceHandlerIF::SEND_READ);
#endif /* OBSW_ADD_RTD_DEVICES */
#if OBSW_ADD_TMP_DEVICES == 1
thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.8, DeviceHandlerIF::GET_READ);
#endif
#if OBSW_ADD_RTD_DEVICES == 1
thisSequence->addSlot(objects::RTD_IC_3, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_4, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_5, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_6, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_7, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_8, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_9, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_10, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_11, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_12, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_13, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_14, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_15, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_16, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_17, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RTD_IC_18, length * 0.8, DeviceHandlerIF::GET_READ);
#endif /* OBSW_ADD_RTD_DEVICES */
#if OBSW_ADD_RAD_SENSORS == 1
/* Radiation sensor */
thisSequence->addSlot(objects::RAD_SENSOR, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::TMP1075_HANDLER_1, length * 0.2, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::TMP1075_HANDLER_2, length * 0.2, DeviceHandlerIF::GET_READ);
#endif
#if OBSW_ADD_SUN_SENSORS == 1
@ -180,180 +113,261 @@ ReturnValue_t pst::pstSpi(FixedTimeslotTaskIF *thisSequence) {
if (addSus0) {
/* Write setup */
thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_0, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_0, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_0, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_0, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_0, length * 0.4, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0.4,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0.4,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_0_N_LOC_XFYFZM_PT_XF, length * 0.4,
DeviceHandlerIF::GET_READ);
}
if (addSus1) {
thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_1, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_1, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_1, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_1, length * 0.4, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0.4,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0.4,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_1_N_LOC_XBYFZM_PT_XB, length * 0.4,
DeviceHandlerIF::GET_READ);
}
if (addSus2) {
thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_2, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_2, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_2, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_2, length * 0.4, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0.4,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0.4,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_2_N_LOC_XFYBZB_PT_YB, length * 0.4,
DeviceHandlerIF::GET_READ);
}
if (addSus3) {
thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_3, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_3, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_3, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_3, length * 0.4, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0.4,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0.4,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_3_N_LOC_XFYBZF_PT_YF, length * 0.4,
DeviceHandlerIF::GET_READ);
}
if (addSus4) {
thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_4, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_4, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_4, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_4, length * 0.4, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0.4,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0.4,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_4_N_LOC_XMYFZF_PT_ZF, length * 0.4,
DeviceHandlerIF::GET_READ);
}
if (addSus5) {
thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_5, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_5, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_5, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_5, length * 0.4, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0.4,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0.4,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_5_N_LOC_XFYMZB_PT_ZB, length * 0.4,
DeviceHandlerIF::GET_READ);
}
if (addSus6) {
thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_6, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_6, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_6, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_6, length * 0.4, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0.4,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0.4,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_6_R_LOC_XFYBZM_PT_XF, length * 0.4,
DeviceHandlerIF::GET_READ);
}
if (addSus7) {
thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_7, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_7, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_7, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_7, length * 0.4, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0.4,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0.4,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_7_R_LOC_XBYBZM_PT_XB, length * 0.4,
DeviceHandlerIF::GET_READ);
}
if (addSus8) {
thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_8, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8, length * 0.4, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0.4,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0.4,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_8_R_LOC_XBYBZB_PT_YB, length * 0.4,
DeviceHandlerIF::GET_READ);
}
if (addSus9) {
thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_9, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_9, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_9, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_9, length * 0.4, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0.4,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0.4,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_9_R_LOC_XBYBZB_PT_YF, length * 0.4,
DeviceHandlerIF::GET_READ);
}
if (addSus10) {
thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_10, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0,
DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_10, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_10, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_10, length * 0.4, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0.4,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0.4,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_10_N_LOC_XMYBZF_PT_ZF, length * 0.4,
DeviceHandlerIF::GET_READ);
}
if (addSus11) {
thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_11, length * 0, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0,
DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_11, length * 0.4, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_11, length * 0.4, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_11, length * 0.4, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0.4,
DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0.4,
DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0.4,
DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::SUS_11_R_LOC_XBYMZB_PT_ZB, length * 0.4,
DeviceHandlerIF::GET_READ);
}
#endif /* OBSW_ADD_SUN_SENSORS == 1 */
#if OBSW_ADD_RW == 1
thisSequence->addSlot(objects::RW1, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RW1, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW1, length * 0.5, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW1, length * 0.65, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW1, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RW2, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RW2, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW2, length * 0.5, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW2, length * 0.65, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW2, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RW3, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RW3, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW3, length * 0.5, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW3, length * 0.65, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW3, length * 0.8, DeviceHandlerIF::GET_READ);
thisSequence->addSlot(objects::RW4, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RW4, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RW4, length * 0.5, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RW4, length * 0.65, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RW4, length * 0.8, DeviceHandlerIF::GET_READ);
#if OBSW_ADD_RAD_SENSORS == 1
/* Radiation sensor */
thisSequence->addSlot(objects::RAD_SENSOR, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.2, DeviceHandlerIF::SEND_WRITE);
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.4, DeviceHandlerIF::GET_WRITE);
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.6, DeviceHandlerIF::SEND_READ);
thisSequence->addSlot(objects::RAD_SENSOR, length * 0.8, DeviceHandlerIF::GET_READ);
#endif
#if OBSW_ADD_ACS_BOARD == 1 && OBSW_ADD_ACS_HANDLERS == 1
@ -464,11 +478,8 @@ ReturnValue_t pst::pstUart(FixedTimeslotTaskIF *thisSequence) {
thisSequence->addSlot(objects::PLOC_MPSOC_HANDLER, length * 0.8, DeviceHandlerIF::GET_READ);
#endif
#ifdef XIPHOS_Q7S
thisSequence->addSlot(objects::PLOC_UPDATER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::PLOC_MEMORY_DUMPER, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
#endif
#if OBSW_ADD_PLOC_SUPERVISOR == 1
thisSequence->addSlot(objects::PLOC_SUPERVISOR_HANDLER, length * 0,
DeviceHandlerIF::PERFORM_OPERATION);
@ -510,11 +521,8 @@ ReturnValue_t pst::pstUart(FixedTimeslotTaskIF *thisSequence) {
ReturnValue_t pst::pstGompaceCan(FixedTimeslotTaskIF *thisSequence) {
uint32_t length = thisSequence->getPeriodMs();
#ifndef TE0720_1CFA
#if Q7S_EM != 1
// PCDU handlers receives two messages and both must be handled
thisSequence->addSlot(objects::PCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::PCDU_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::P60DOCK_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
thisSequence->addSlot(objects::PDU1_HANDLER, length * 0, DeviceHandlerIF::PERFORM_OPERATION);
@ -544,8 +552,6 @@ ReturnValue_t pst::pstGompaceCan(FixedTimeslotTaskIF *thisSequence) {
sif::error << "GomSpace PST initialization failed" << std::endl;
return HasReturnvaluesIF::RETURN_FAILED;
}
#endif /* Q7S_EM == 0 */
#endif
static_cast<void>(length);
return HasReturnvaluesIF::RETURN_OK;
}

View File

@ -46,6 +46,8 @@ ReturnValue_t pstUart(FixedTimeslotTaskIF* thisSequence);
ReturnValue_t pstSpi(FixedTimeslotTaskIF* thisSequence);
ReturnValue_t pstSpiRw(FixedTimeslotTaskIF* thisSequence);
ReturnValue_t pstI2c(FixedTimeslotTaskIF* thisSequence);
/**

View File

@ -1,23 +0,0 @@
#ifndef CONFIG_TMTC_PUSIDS_HPP_
#define CONFIG_TMTC_PUSIDS_HPP_
namespace pus {
enum Ids {
PUS_SERVICE_1 = 1,
PUS_SERVICE_2 = 2,
PUS_SERVICE_3 = 3,
PUS_SERVICE_3_PSB = 3,
PUS_SERVICE_5 = 5,
PUS_SERVICE_6 = 6,
PUS_SERVICE_8 = 8,
PUS_SERVICE_9 = 9,
PUS_SERVICE_17 = 17,
PUS_SERVICE_19 = 19,
PUS_SERVICE_20 = 20,
PUS_SERVICE_23 = 23,
PUS_SERVICE_200 = 200,
PUS_SERVICE_201 = 201,
};
};
#endif /* CONFIG_TMTC_PUSIDS_HPP_ */

View File

@ -1,10 +1,3 @@
target_sources(${OBSW_NAME} PUBLIC
PapbVcInterface.cpp
Ptme.cpp
PdecHandler.cpp
PdecConfig.cpp
PtmeConfig.cpp
AxiPtmeConfig.cpp
)
target_sources(
${OBSW_NAME} PUBLIC PapbVcInterface.cpp Ptme.cpp PdecHandler.cpp
PdecConfig.cpp PtmeConfig.cpp AxiPtmeConfig.cpp)

View File

@ -42,17 +42,17 @@ void PapbVcInterface::startPacketTransfer() { *vcBaseReg = CONFIG_START; }
void PapbVcInterface::endPacketTransfer() { *vcBaseReg = CONFIG_END; }
ReturnValue_t PapbVcInterface::pollPapbBusySignal() {
int papbBusyState = 0;
gpio::Levels papbBusyState = gpio::Levels::LOW;
ReturnValue_t result = RETURN_OK;
/** Check if PAPB interface is ready to receive data */
result = gpioComIF->readGpio(papbBusyId, &papbBusyState);
result = gpioComIF->readGpio(papbBusyId, papbBusyState);
if (result != RETURN_OK) {
sif::warning << "PapbVcInterface::pollPapbBusySignal: Failed to read papb busy signal"
<< std::endl;
return RETURN_FAILED;
}
if (!papbBusyState) {
if (papbBusyState == gpio::Levels::LOW) {
sif::warning << "PapbVcInterface::pollPapbBusySignal: PAPB busy" << std::endl;
return PAPB_BUSY;
}
@ -62,9 +62,9 @@ ReturnValue_t PapbVcInterface::pollPapbBusySignal() {
void PapbVcInterface::isVcInterfaceBufferEmpty() {
ReturnValue_t result = RETURN_OK;
int papbEmptyState = 1;
gpio::Levels papbEmptyState = gpio::Levels::HIGH;
result = gpioComIF->readGpio(papbEmptyId, &papbEmptyState);
result = gpioComIF->readGpio(papbEmptyId, papbEmptyState);
if (result != RETURN_OK) {
sif::warning << "PapbVcInterface::isVcInterfaceBufferEmpty: Failed to read papb empty signal"
@ -72,7 +72,7 @@ void PapbVcInterface::isVcInterfaceBufferEmpty() {
return;
}
if (papbEmptyState == 1) {
if (papbEmptyState == gpio::Levels::HIGH) {
sif::debug << "PapbVcInterface::isVcInterfaceBufferEmpty: Buffer is empty" << std::endl;
} else {
sif::debug << "PapbVcInterface::isVcInterfaceBufferEmpty: Buffer is not empty" << std::endl;

View File

@ -6,7 +6,6 @@
#include <cstring>
#include <sstream>
#include "OBSWConfig.h"
#include "fsfw/ipc/QueueFactory.h"
#include "fsfw/objectmanager/ObjectManager.h"
#include "fsfw/serviceinterface/ServiceInterface.h"

View File

@ -1,7 +1 @@
target_sources(${OBSW_NAME} PUBLIC
utility.cpp
)
target_sources(${OBSW_NAME} PUBLIC utility.cpp)