Merge remote-tracking branch 'origin/develop' into feature_allow_side_switch
All checks were successful
EIVE/eive-obsw/pipeline/pr-develop This commit looks good

This commit is contained in:
2023-03-24 17:29:13 +01:00
266 changed files with 8685 additions and 4914 deletions

View File

@ -314,7 +314,7 @@ void ObjectFactory::createRtdComponents(std::string spiDev, GpioIF* gpioComIF,
void ObjectFactory::createScexComponents(std::string uartDev, PowerSwitchIF* pwrSwitcher,
SdCardMountedIF& mountedIF, bool onImmediately,
std::optional<power::Switch_t> switchId) {
auto* cookie = new SerialCookie(objects::SCEX, uartDev, uart::SCEX_BAUD, 4096);
auto* cookie = new SerialCookie(objects::SCEX, uartDev, serial::SCEX_BAUD, 4096);
cookie->setTwoStopBits();
// cookie->setParityEven();
auto scexUartReader = new ScexUartReader(objects::SCEX_UART_READER);
@ -325,7 +325,7 @@ void ObjectFactory::createScexComponents(std::string uartDev, PowerSwitchIF* pwr
if (switchId) {
scexHandler->setPowerSwitcher(*pwrSwitcher, switchId.value());
}
scexHandler->connectModeTreeParent(satsystem::pl::SUBSYSTEM);
scexHandler->connectModeTreeParent(satsystem::payload::SUBSYSTEM);
}
AcsController* ObjectFactory::createAcsController(bool connectSubsystem) {
@ -341,9 +341,3 @@ void ObjectFactory::gpioChecker(ReturnValue_t result, std::string output) {
sif::error << "ObjectFactory: Adding GPIOs failed for " << output << std::endl;
}
}
void ObjectFactory::addTmtcIpCoresToFunnels(CcsdsIpCoreHandler& ipCoreHandler,
PusTmFunnel& pusFunnel, CfdpTmFunnel& cfdpFunnel) {
cfdpFunnel.addDestination("PTME IP Core", ipCoreHandler, config::LIVE_TM);
pusFunnel.addDestination("PTME IP Core", ipCoreHandler, config::LIVE_TM);
}

View File

@ -33,6 +33,4 @@ void gpioChecker(ReturnValue_t result, std::string output);
AcsController* createAcsController(bool connectSubsystem);
void addTmtcIpCoresToFunnels(CcsdsIpCoreHandler& ipCoreHandler, PusTmFunnel& pusFunnel,
CfdpTmFunnel& cfdpFunnel);
} // namespace ObjectFactory

View File

@ -14,7 +14,10 @@
using namespace GOMSPACE;
CspComIF::CspComIF(object_id_t objectId) : SystemObject(objectId) {}
CspComIF::CspComIF(object_id_t objectId, const char* routeTaskName, uint32_t routerRealTimePriority)
: SystemObject(objectId),
routerRealTimePriority(routerRealTimePriority),
routerTaskName(routeTaskName) {}
CspComIF::~CspComIF() {}
@ -57,10 +60,8 @@ ReturnValue_t CspComIF::initializeInterface(CookieIF* cookie) {
}
/* Start the route task */
unsigned int task_stack_size = 500;
unsigned int priority = 0;
result = csp_route_start_task(task_stack_size, priority);
if (result != CSP_ERR_NONE) {
result = startRouterTask();
if (result != returnvalue::OK) {
sif::error << "Failed to start csp route task" << std::endl;
return returnvalue::FAILED;
}
@ -343,3 +344,55 @@ void CspComIF::initiatePingRequest(uint8_t cspAddress, uint16_t querySize) {
memcpy(replyBuffer, &replyTime, sizeof(replyTime));
iter->second.replyLen = sizeof(replyTime);
}
ReturnValue_t CspComIF::startRouterTask() {
pthread_attr_t attr;
int res = pthread_attr_init(&attr);
if (res) {
return returnvalue::FAILED;
}
pthread_attr_setdetachstate(&attr, PTHREAD_CREATE_DETACHED);
res = pthread_attr_setinheritsched(&attr, PTHREAD_EXPLICIT_SCHED);
if (res != 0) {
return returnvalue::FAILED;
}
// Set scheduling policy to SCHED_RR
res = pthread_attr_setschedpolicy(&attr, SCHED_RR);
if (res) {
pthread_attr_destroy(&attr);
return returnvalue::FAILED;
}
struct sched_param sched_param;
sched_param.sched_priority = routerRealTimePriority;
res = pthread_attr_setschedparam(&attr, &sched_param);
if (res) {
pthread_attr_destroy(&attr);
return returnvalue::FAILED;
}
res = pthread_create(&routerTaskHandle, &attr, routerWorkWrapper, NULL);
if (res) {
pthread_attr_destroy(&attr);
return returnvalue::FAILED;
}
res = pthread_setname_np(routerTaskHandle, routerTaskName);
if (res) {
pthread_attr_destroy(&attr);
return returnvalue::FAILED;
}
pthread_attr_destroy(&attr);
return returnvalue::OK;
}
void* CspComIF::routerWorkWrapper(void* args) {
/* Here there be routing */
while (1) {
csp_route_work(FIFO_TIMEOUT);
}
return nullptr;
}

View File

@ -2,9 +2,11 @@
#define LINUX_CSP_CSPCOMIF_H_
#include <csp/csp.h>
#include <csp/csp_autoconfig.h>
#include <fsfw/devicehandlers/DeviceCommunicationIF.h>
#include <fsfw/objectmanager/SystemObject.h>
#include <fsfw/returnvalues/returnvalue.h>
#include <pthread.h>
#include <unordered_map>
#include <vector>
@ -17,7 +19,7 @@
*/
class CspComIF : public DeviceCommunicationIF, public SystemObject {
public:
CspComIF(object_id_t objectId);
CspComIF(object_id_t objectId, const char *routeTaskName, uint32_t routerRealTimePriority);
virtual ~CspComIF();
ReturnValue_t initializeInterface(CookieIF *cookie) override;
@ -27,6 +29,13 @@ class CspComIF : public DeviceCommunicationIF, public SystemObject {
ReturnValue_t readReceivedMessage(CookieIF *cookie, uint8_t **readData, size_t *readLen) override;
private:
#ifdef CSP_USE_RDP
//! If RDP is enabled, the router needs to awake some times to check timeouts
static constexpr uint32_t FIFO_TIMEOUT = 100;
#else
//! If no RDP, the router can sleep untill data arrives
static constexpr uint32_t FIFO_TIMEOUT = CSP_MAX_DELAY;
#endif
/**
* @brief This function initiates the CSP transfer.
*
@ -56,6 +65,10 @@ class CspComIF : public DeviceCommunicationIF, public SystemObject {
/* This is the CSP address of the OBC. */
node_t cspOwnAddress = 1;
pthread_t routerTaskHandle{};
uint32_t routerRealTimePriority = 0;
const char *routerTaskName;
/* Interface struct for csp protocol stack */
csp_iface_t csp_if;
char canInterface[5] = "can0";
@ -72,6 +85,9 @@ class CspComIF : public DeviceCommunicationIF, public SystemObject {
* @brief This function initiates the ping request.
*/
void initiatePingRequest(uint8_t cspAddress, uint16_t querySize);
ReturnValue_t startRouterTask();
static void *routerWorkWrapper(void *args);
};
#endif /* LINUX_CSP_CSPCOMIF_H_ */

View File

@ -4,6 +4,7 @@
#include <fsfw/globalfunctions/arrayprinter.h>
#include <fsfw/tasks/SemaphoreFactory.h>
#include <fsfw/tasks/TaskFactory.h>
#include <fsfw/timemanager/Stopwatch.h>
#include <fsfw_hal/devicehandlers/devicedefinitions/gyroL3gHelpers.h>
#include <fsfw_hal/devicehandlers/devicedefinitions/mgmLis3Helpers.h>
#include <fsfw_hal/linux/UnixFileGuard.h>
@ -25,20 +26,24 @@ AcsBoardPolling::AcsBoardPolling(object_id_t objectId, SpiComIF& lowLevelComIF,
ReturnValue_t AcsBoardPolling::performOperation(uint8_t operationCode) {
while (true) {
ipcLock->lockMutex();
ipcLock->lockMutex(LOCK_TYPE, LOCK_TIMEOUT);
state = InternalState::IDLE;
ipcLock->unlockMutex();
semaphore->acquire();
// Give all tasks or the PST some time to submit all consecutive requests.
TaskFactory::delayTask(2);
gyroAdisHandler(gyro0Adis);
gyroAdisHandler(gyro2Adis);
gyroL3gHandler(gyro1L3g);
gyroL3gHandler(gyro3L3g);
mgmRm3100Handler(mgm1Rm3100);
mgmRm3100Handler(mgm3Rm3100);
mgmLis3Handler(mgm0Lis3);
mgmLis3Handler(mgm2Lis3);
{
// Measured to take 0-1 ms in debug build.
// Stopwatch watch;
gyroAdisHandler(gyro0Adis);
gyroAdisHandler(gyro2Adis);
gyroL3gHandler(gyro1L3g);
gyroL3gHandler(gyro3L3g);
mgmRm3100Handler(mgm1Rm3100);
mgmRm3100Handler(mgm3Rm3100);
mgmLis3Handler(mgm0Lis3);
mgmLis3Handler(mgm2Lis3);
}
// To prevent task being not reactivated by tardy tasks
TaskFactory::delayTask(20);
}
@ -105,12 +110,10 @@ ReturnValue_t AcsBoardPolling::sendMessage(CookieIF* cookie, const uint8_t* send
return returnvalue::FAILED;
}
auto* req = reinterpret_cast<const acs::Adis1650XRequest*>(sendData);
MutexGuard mg(ipcLock);
if (req->mode != adis.mode) {
if (req->mode == acs::SimpleSensorMode::NORMAL) {
adis.type = req->type;
adis.countdown.setTimeout(adis1650x::START_UP_TIME);
adis.countdown.resetTimer();
if (adis.type == adis1650x::Type::ADIS16507) {
adis.ownReply.data.accelScaling = adis1650x::ACCELEROMETER_RANGE_16507;
} else if (adis.type == adis1650x::Type::ADIS16505) {
@ -135,7 +138,6 @@ ReturnValue_t AcsBoardPolling::sendMessage(CookieIF* cookie, const uint8_t* send
return returnvalue::FAILED;
}
auto* req = reinterpret_cast<const acs::GyroL3gRequest*>(sendData);
MutexGuard mg(ipcLock);
if (req->mode != gyro.mode) {
if (req->mode == acs::SimpleSensorMode::NORMAL) {
std::memcpy(gyro.sensorCfg, req->ctrlRegs, 5);
@ -154,7 +156,6 @@ ReturnValue_t AcsBoardPolling::sendMessage(CookieIF* cookie, const uint8_t* send
return returnvalue::FAILED;
}
auto* req = reinterpret_cast<const acs::MgmLis3Request*>(sendData);
MutexGuard mg(ipcLock);
if (req->mode != mgm.mode) {
if (req->mode == acs::SimpleSensorMode::NORMAL) {
mgm.performStartup = true;
@ -173,7 +174,6 @@ ReturnValue_t AcsBoardPolling::sendMessage(CookieIF* cookie, const uint8_t* send
return returnvalue::FAILED;
}
auto* req = reinterpret_cast<const acs::MgmRm3100Request*>(sendData);
MutexGuard mg(ipcLock);
if (req->mode != mgm.mode) {
if (req->mode == acs::SimpleSensorMode::NORMAL) {
mgm.performStartup = true;
@ -184,45 +184,47 @@ ReturnValue_t AcsBoardPolling::sendMessage(CookieIF* cookie, const uint8_t* send
}
return returnvalue::OK;
};
switch (spiCookie->getChipSelectPin()) {
case (gpioIds::MGM_0_LIS3_CS): {
handleLis3Request(mgm0Lis3);
break;
{
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
switch (spiCookie->getChipSelectPin()) {
case (gpioIds::MGM_0_LIS3_CS): {
handleLis3Request(mgm0Lis3);
break;
}
case (gpioIds::MGM_1_RM3100_CS): {
handleRm3100Request(mgm1Rm3100);
break;
}
case (gpioIds::MGM_2_LIS3_CS): {
handleLis3Request(mgm2Lis3);
break;
}
case (gpioIds::MGM_3_RM3100_CS): {
handleRm3100Request(mgm3Rm3100);
break;
}
case (gpioIds::GYRO_0_ADIS_CS): {
handleAdisRequest(gyro0Adis);
break;
}
case (gpioIds::GYRO_2_ADIS_CS): {
handleAdisRequest(gyro2Adis);
break;
}
case (gpioIds::GYRO_1_L3G_CS): {
handleL3gRequest(gyro1L3g);
break;
}
case (gpioIds::GYRO_3_L3G_CS): {
handleL3gRequest(gyro3L3g);
break;
}
}
case (gpioIds::MGM_1_RM3100_CS): {
handleRm3100Request(mgm1Rm3100);
break;
}
case (gpioIds::MGM_2_LIS3_CS): {
handleLis3Request(mgm2Lis3);
break;
}
case (gpioIds::MGM_3_RM3100_CS): {
handleRm3100Request(mgm3Rm3100);
break;
}
case (gpioIds::GYRO_0_ADIS_CS): {
handleAdisRequest(gyro0Adis);
break;
}
case (gpioIds::GYRO_2_ADIS_CS): {
handleAdisRequest(gyro2Adis);
break;
}
case (gpioIds::GYRO_1_L3G_CS): {
handleL3gRequest(gyro1L3g);
break;
}
case (gpioIds::GYRO_3_L3G_CS): {
handleL3gRequest(gyro3L3g);
break;
if (state == InternalState::IDLE) {
state = InternalState::IS_BUSY;
}
}
MutexGuard mg(ipcLock);
if (state == InternalState::IDLE) {
state = InternalState::BUSY;
semaphore->release();
}
semaphore->release();
return returnvalue::OK;
}
@ -238,7 +240,7 @@ ReturnValue_t AcsBoardPolling::readReceivedMessage(CookieIF* cookie, uint8_t** b
if (spiCookie == nullptr) {
return returnvalue::FAILED;
}
MutexGuard mg(ipcLock);
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
auto handleAdisReply = [&](GyroAdis& gyro) {
std::memcpy(&gyro.readerReply, &gyro.ownReply, sizeof(acs::Adis1650XReply));
*buffer = reinterpret_cast<uint8_t*>(&gyro.readerReply);
@ -294,10 +296,10 @@ ReturnValue_t AcsBoardPolling::readReceivedMessage(CookieIF* cookie, uint8_t** b
void AcsBoardPolling::gyroL3gHandler(GyroL3g& l3g) {
ReturnValue_t result;
acs::SimpleSensorMode mode;
bool gyroPerformStartup;
acs::SimpleSensorMode mode = acs::SimpleSensorMode::OFF;
bool gyroPerformStartup = false;
{
MutexGuard mg(ipcLock);
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
mode = l3g.mode;
gyroPerformStartup = l3g.performStartup;
}
@ -320,7 +322,7 @@ void AcsBoardPolling::gyroL3gHandler(GyroL3g& l3g) {
if (result != returnvalue::OK) {
l3g.replyResult = returnvalue::OK;
}
MutexGuard mg(ipcLock);
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
// Cross check configuration as verification that communication is working
for (uint8_t idx = 0; idx < 5; idx++) {
if (rawReply[idx + 1] != l3g.sensorCfg[idx]) {
@ -345,7 +347,7 @@ void AcsBoardPolling::gyroL3gHandler(GyroL3g& l3g) {
l3g.replyResult = returnvalue::FAILED;
return;
}
MutexGuard mg(ipcLock);
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
// The regular read function always returns the full sensor config as well. Use that
// to verify communications.
for (uint8_t idx = 0; idx < 5; idx++) {
@ -440,112 +442,116 @@ ReturnValue_t AcsBoardPolling::readAdisCfg(SpiCookie& cookie, size_t transferLen
void AcsBoardPolling::gyroAdisHandler(GyroAdis& gyro) {
ReturnValue_t result;
acs::SimpleSensorMode mode;
acs::SimpleSensorMode mode = acs::SimpleSensorMode::OFF;
bool cdHasTimedOut = false;
bool mustPerformStartup = false;
{
MutexGuard mg(ipcLock);
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
mode = gyro.mode;
cdHasTimedOut = gyro.countdown.hasTimedOut();
mustPerformStartup = gyro.performStartup;
}
if (mode == acs::SimpleSensorMode::NORMAL and cdHasTimedOut) {
if (mustPerformStartup) {
uint8_t regList[6];
// Read configuration
regList[0] = adis1650x::DIAG_STAT_REG;
regList[1] = adis1650x::FILTER_CTRL_REG;
regList[2] = adis1650x::RANG_MDL_REG;
regList[3] = adis1650x::MSC_CTRL_REG;
regList[4] = adis1650x::DEC_RATE_REG;
regList[5] = adis1650x::PROD_ID_REG;
size_t transferLen =
adis1650x::prepareReadCommand(regList, sizeof(regList), cmdBuf.data(), cmdBuf.size());
result = readAdisCfg(*gyro.cookie, transferLen);
if (result != returnvalue::OK) {
gyro.replyResult = result;
return;
}
result = spiComIF.readReceivedMessage(gyro.cookie, &rawReply, &dummy);
if (result != returnvalue::OK or rawReply == nullptr) {
gyro.replyResult = result;
return;
}
uint16_t prodId = (rawReply[12] << 8) | rawReply[13];
if (((gyro.type == adis1650x::Type::ADIS16505) and (prodId != adis1650x::PROD_ID_16505)) or
((gyro.type == adis1650x::Type::ADIS16507) and (prodId != adis1650x::PROD_ID_16507))) {
sif::warning << "AcsPollingTask: Invalid ADIS product ID " << prodId << std::endl;
gyro.replyResult = returnvalue::FAILED;
return;
}
MutexGuard mg(ipcLock);
gyro.ownReply.cfgWasSet = true;
gyro.ownReply.cfg.diagStat = (rawReply[2] << 8) | rawReply[3];
gyro.ownReply.cfg.filterSetting = (rawReply[4] << 8) | rawReply[5];
gyro.ownReply.cfg.rangMdl = (rawReply[6] << 8) | rawReply[7];
gyro.ownReply.cfg.mscCtrlReg = (rawReply[8] << 8) | rawReply[9];
gyro.ownReply.cfg.decRateReg = (rawReply[10] << 8) | rawReply[11];
gyro.ownReply.cfg.prodId = prodId;
gyro.ownReply.data.sensitivity = adis1650x::rangMdlToSensitivity(gyro.ownReply.cfg.rangMdl);
gyro.performStartup = false;
}
// Read regular registers
std::memcpy(cmdBuf.data(), adis1650x::BURST_READ_ENABLE.data(),
adis1650x::BURST_READ_ENABLE.size());
std::memset(cmdBuf.data() + 2, 0, 10 * 2);
result = spiComIF.sendMessage(gyro.cookie, cmdBuf.data(), adis1650x::SENSOR_READOUT_SIZE);
if (mode == acs::SimpleSensorMode::OFF) {
return;
}
if (not cdHasTimedOut) {
return;
}
if (mustPerformStartup) {
uint8_t regList[6];
// Read configuration
regList[0] = adis1650x::DIAG_STAT_REG;
regList[1] = adis1650x::FILTER_CTRL_REG;
regList[2] = adis1650x::RANG_MDL_REG;
regList[3] = adis1650x::MSC_CTRL_REG;
regList[4] = adis1650x::DEC_RATE_REG;
regList[5] = adis1650x::PROD_ID_REG;
size_t transferLen =
adis1650x::prepareReadCommand(regList, sizeof(regList), cmdBuf.data(), cmdBuf.size());
result = readAdisCfg(*gyro.cookie, transferLen);
if (result != returnvalue::OK) {
gyro.replyResult = returnvalue::FAILED;
gyro.replyResult = result;
return;
}
result = spiComIF.readReceivedMessage(gyro.cookie, &rawReply, &dummy);
if (result != returnvalue::OK or rawReply == nullptr) {
gyro.replyResult = result;
return;
}
uint16_t prodId = (rawReply[12] << 8) | rawReply[13];
if (((gyro.type == adis1650x::Type::ADIS16505) and (prodId != adis1650x::PROD_ID_16505)) or
((gyro.type == adis1650x::Type::ADIS16507) and (prodId != adis1650x::PROD_ID_16507))) {
sif::warning << "AcsPollingTask: Invalid ADIS product ID " << prodId << std::endl;
gyro.replyResult = returnvalue::FAILED;
return;
}
uint16_t checksum = (rawReply[20] << 8) | rawReply[21];
// Now verify the read checksum with the expected checksum according to datasheet p. 20
uint16_t calcChecksum = 0;
for (size_t idx = 2; idx < 20; idx++) {
calcChecksum += rawReply[idx];
}
if (checksum != calcChecksum) {
sif::warning << "AcsPollingTask: Invalid ADIS reply checksum" << std::endl;
gyro.replyResult = returnvalue::FAILED;
return;
}
auto burstMode = adis1650x::burstModeFromMscCtrl(gyro.ownReply.cfg.mscCtrlReg);
if (burstMode != adis1650x::BurstModes::BURST_16_BURST_SEL_0) {
sif::error << "GyroADIS1650XHandler::interpretDeviceReply: Analysis for select burst mode"
" not implemented!"
<< std::endl;
gyro.replyResult = returnvalue::FAILED;
return;
}
MutexGuard mg(ipcLock);
gyro.ownReply.dataWasSet = true;
gyro.ownReply.cfg.diagStat = rawReply[2] << 8 | rawReply[3];
gyro.ownReply.data.angVelocities[0] = (rawReply[4] << 8) | rawReply[5];
gyro.ownReply.data.angVelocities[1] = (rawReply[6] << 8) | rawReply[7];
gyro.ownReply.data.angVelocities[2] = (rawReply[8] << 8) | rawReply[9];
gyro.ownReply.data.accelerations[0] = (rawReply[10] << 8) | rawReply[11];
gyro.ownReply.data.accelerations[1] = (rawReply[12] << 8) | rawReply[13];
gyro.ownReply.data.accelerations[2] = (rawReply[14] << 8) | rawReply[15];
gyro.ownReply.data.temperatureRaw = (rawReply[16] << 8) | rawReply[17];
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
gyro.ownReply.cfgWasSet = true;
gyro.ownReply.cfg.diagStat = (rawReply[2] << 8) | rawReply[3];
gyro.ownReply.cfg.filterSetting = (rawReply[4] << 8) | rawReply[5];
gyro.ownReply.cfg.rangMdl = (rawReply[6] << 8) | rawReply[7];
gyro.ownReply.cfg.mscCtrlReg = (rawReply[8] << 8) | rawReply[9];
gyro.ownReply.cfg.decRateReg = (rawReply[10] << 8) | rawReply[11];
gyro.ownReply.cfg.prodId = prodId;
gyro.ownReply.data.sensitivity = adis1650x::rangMdlToSensitivity(gyro.ownReply.cfg.rangMdl);
gyro.performStartup = false;
}
// Read regular registers
std::memcpy(cmdBuf.data(), adis1650x::BURST_READ_ENABLE.data(),
adis1650x::BURST_READ_ENABLE.size());
std::memset(cmdBuf.data() + 2, 0, 10 * 2);
result = spiComIF.sendMessage(gyro.cookie, cmdBuf.data(), adis1650x::SENSOR_READOUT_SIZE);
if (result != returnvalue::OK) {
gyro.replyResult = returnvalue::FAILED;
return;
}
result = spiComIF.readReceivedMessage(gyro.cookie, &rawReply, &dummy);
if (result != returnvalue::OK or rawReply == nullptr) {
gyro.replyResult = returnvalue::FAILED;
return;
}
uint16_t checksum = (rawReply[20] << 8) | rawReply[21];
// Now verify the read checksum with the expected checksum according to datasheet p. 20
uint16_t calcChecksum = 0;
for (size_t idx = 2; idx < 20; idx++) {
calcChecksum += rawReply[idx];
}
if (checksum != calcChecksum) {
sif::warning << "AcsPollingTask: Invalid ADIS reply checksum" << std::endl;
gyro.replyResult = returnvalue::FAILED;
return;
}
auto burstMode = adis1650x::burstModeFromMscCtrl(gyro.ownReply.cfg.mscCtrlReg);
if (burstMode != adis1650x::BurstModes::BURST_16_BURST_SEL_0) {
sif::error << "GyroADIS1650XHandler::interpretDeviceReply: Analysis for select burst mode"
" not implemented!"
<< std::endl;
gyro.replyResult = returnvalue::FAILED;
return;
}
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
gyro.ownReply.dataWasSet = true;
gyro.ownReply.cfg.diagStat = rawReply[2] << 8 | rawReply[3];
gyro.ownReply.data.angVelocities[0] = (rawReply[4] << 8) | rawReply[5];
gyro.ownReply.data.angVelocities[1] = (rawReply[6] << 8) | rawReply[7];
gyro.ownReply.data.angVelocities[2] = (rawReply[8] << 8) | rawReply[9];
gyro.ownReply.data.accelerations[0] = (rawReply[10] << 8) | rawReply[11];
gyro.ownReply.data.accelerations[1] = (rawReply[12] << 8) | rawReply[13];
gyro.ownReply.data.accelerations[2] = (rawReply[14] << 8) | rawReply[15];
gyro.ownReply.data.temperatureRaw = (rawReply[16] << 8) | rawReply[17];
}
void AcsBoardPolling::mgmLis3Handler(MgmLis3& mgm) {
ReturnValue_t result;
acs::SimpleSensorMode mode;
acs::SimpleSensorMode mode = acs::SimpleSensorMode::OFF;
bool mustPerformStartup = false;
{
MutexGuard mg(ipcLock);
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
mode = mgm.mode;
mustPerformStartup = mgm.performStartup;
}
@ -605,7 +611,7 @@ void AcsBoardPolling::mgmLis3Handler(MgmLis3& mgm) {
return;
}
{
MutexGuard mg(ipcLock);
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
mgm.ownReply.dataWasSet = true;
mgm.ownReply.sensitivity = mgmLis3::getSensitivityFactor(mgmLis3::getSensitivity(mgm.cfg[1]));
mgm.ownReply.mgmValuesRaw[0] =
@ -627,7 +633,7 @@ void AcsBoardPolling::mgmLis3Handler(MgmLis3& mgm) {
mgm.replyResult = result;
return;
}
MutexGuard mg(ipcLock);
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
mgm.ownReply.temperatureWasSet = true;
mgm.ownReply.temperatureRaw = (rawReply[2] << 8) | rawReply[1];
}
@ -635,10 +641,10 @@ void AcsBoardPolling::mgmLis3Handler(MgmLis3& mgm) {
void AcsBoardPolling::mgmRm3100Handler(MgmRm3100& mgm) {
ReturnValue_t result;
acs::SimpleSensorMode mode;
acs::SimpleSensorMode mode = acs::SimpleSensorMode::OFF;
bool mustPerformStartup = false;
{
MutexGuard mg(ipcLock);
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
mode = mgm.mode;
mustPerformStartup = mgm.performStartup;
}
@ -712,7 +718,7 @@ void AcsBoardPolling::mgmRm3100Handler(MgmRm3100& mgm) {
mgm.replyResult = result;
return;
}
MutexGuard mg(ipcLock);
MutexGuard mg(ipcLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
for (uint8_t idx = 0; idx < 3; idx++) {
// Hardcoded, but note that the gain depends on the cycle count
// value which is configurable!

View File

@ -20,8 +20,11 @@ class AcsBoardPolling : public SystemObject,
ReturnValue_t initialize() override;
private:
enum class InternalState { IDLE, BUSY } state = InternalState::IDLE;
enum class InternalState { IDLE, IS_BUSY } state = InternalState::IDLE;
MutexIF* ipcLock;
static constexpr MutexIF::TimeoutType LOCK_TYPE = MutexIF::TimeoutType::WAITING;
static constexpr uint32_t LOCK_TIMEOUT = 20;
static constexpr char LOCK_CTX[] = "AcsBoardPolling";
SemaphoreIF* semaphore;
std::array<uint8_t, 32> cmdBuf;

View File

@ -11,7 +11,8 @@ target_sources(
ScexDleParser.cpp
ScexHelper.cpp
RwPollingTask.cpp
AcsBoardPolling.cpp)
AcsBoardPolling.cpp
SyrlinksComHandler.cpp)
add_subdirectory(ploc)

View File

@ -19,9 +19,7 @@
GpsHyperionLinuxController::GpsHyperionLinuxController(object_id_t objectId, object_id_t parentId,
bool debugHyperionGps)
: ExtendedControllerBase(objectId), gpsSet(this), debugHyperionGps(debugHyperionGps) {
timeUpdateCd.resetTimer();
}
: ExtendedControllerBase(objectId), gpsSet(this), debugHyperionGps(debugHyperionGps) {}
GpsHyperionLinuxController::~GpsHyperionLinuxController() {
gps_stream(&gps, WATCH_DISABLE, nullptr);
@ -196,8 +194,8 @@ ReturnValue_t GpsHyperionLinuxController::handleGpsReadData() {
if (mode != MODE_OFF) {
if (maxTimeToReachFix.hasTimedOut() and oneShotSwitches.cantGetFixSwitch) {
sif::warning << "GpsHyperionLinuxController: No mode could be set in allowed "
<< maxTimeToReachFix.timeout / 1000 << " seconds" << std::endl;
triggerEvent(GpsHyperion::CANT_GET_FIX, maxTimeToReachFix.timeout);
<< maxTimeToReachFix.getTimeoutMs() / 1000 << " seconds" << std::endl;
triggerEvent(GpsHyperion::CANT_GET_FIX, maxTimeToReachFix.getTimeoutMs());
oneShotSwitches.cantGetFixSwitch = false;
}
modeIsSet = false;
@ -216,16 +214,14 @@ ReturnValue_t GpsHyperionLinuxController::handleGpsReadData() {
}
bool validFix = false;
uint8_t newFix = 0;
if (modeIsSet) {
// 0: Not seen, 1: No fix, 2: 2D-Fix, 3: 3D-Fix
if (gps.fix.mode == 2 or gps.fix.mode == 3) {
validFix = true;
}
if (gpsSet.fixMode.value != gps.fix.mode) {
triggerEvent(GpsHyperion::GPS_FIX_CHANGE, gpsSet.fixMode.value, gps.fix.mode);
}
gpsSet.fixMode.value = gps.fix.mode;
if (gps.fix.mode == 0 or gps.fix.mode == 1) {
newFix = gps.fix.mode;
if (newFix == 0 or newFix == 1) {
if (modeCommanded and maxTimeToReachFix.hasTimedOut()) {
// We are supposed to be on and functioning, but no fix was found
if (mode == MODE_ON or mode == MODE_NORMAL) {
@ -235,6 +231,10 @@ ReturnValue_t GpsHyperionLinuxController::handleGpsReadData() {
}
}
}
if (gpsSet.fixMode.value != newFix) {
triggerEvent(GpsHyperion::GPS_FIX_CHANGE, gpsSet.fixMode.value, newFix);
}
gpsSet.fixMode = newFix;
gpsSet.fixMode.setValid(modeIsSet);
// Only set on specific messages, so only set a valid flag to invalid
@ -302,7 +302,10 @@ ReturnValue_t GpsHyperionLinuxController::handleGpsReadData() {
// TIME is set for every message, no need for a counter
bool timeValid = false;
if (TIME_SET == (TIME_SET & gps.set)) {
timeValid = true;
// To prevent totally incorrect times from being declared valid.
if (gpsSet.satInView.isValid() and gpsSet.satInView.value >= 1) {
timeValid = true;
}
timeval time = {};
#if LIBGPS_VERSION_MINOR <= 17
gpsSet.unixSeconds.value = std::floor(gps.fix.time);

View File

@ -23,7 +23,8 @@
*/
class GpsHyperionLinuxController : public ExtendedControllerBase {
public:
static constexpr uint32_t MAX_SECONDS_TO_REACH_FIX = 60 * 60 * 5;
// 30 minutes
static constexpr uint32_t MAX_SECONDS_TO_REACH_FIX = 60 * 30;
enum ReadModes { SHM = 0, SOCKET = 1 };
@ -79,7 +80,6 @@ class GpsHyperionLinuxController : public ExtendedControllerBase {
bool debugHyperionGps = false;
int32_t noModeSetCntr = 0;
Countdown timeUpdateCd = Countdown(60);
// Returns true if the function should be called again or false if other
// controller handling can be done.

View File

@ -10,7 +10,8 @@
#include "fsfw/FSFW.h"
ImtqPollingTask::ImtqPollingTask(object_id_t imtqPollingTask) : SystemObject(imtqPollingTask) {
ImtqPollingTask::ImtqPollingTask(object_id_t imtqPollingTask, std::atomic_uint16_t& i2cFatalErrors)
: SystemObject(imtqPollingTask), i2cFatalErrors(i2cFatalErrors) {
semaphore = SemaphoreFactory::instance()->createBinarySemaphore();
semaphore->acquire();
ipcLock = MutexFactory::instance()->createMutex();
@ -28,6 +29,8 @@ ReturnValue_t ImtqPollingTask::performOperation(uint8_t operationCode) {
// Stopwatch watch;
switch (currentRequest) {
case imtq::RequestType::MEASURE_NO_ACTUATION: {
// Measured to take 24 ms for debug and release builds.
// Stopwatch watch;
handleMeasureStep();
break;
}
@ -35,6 +38,9 @@ ReturnValue_t ImtqPollingTask::performOperation(uint8_t operationCode) {
handleActuateStep();
break;
}
default: {
break;
}
};
}
return returnvalue::OK;
@ -44,6 +50,9 @@ void ImtqPollingTask::handleMeasureStep() {
size_t replyLen = 0;
uint8_t* replyPtr;
ImtqRepliesDefault replies(replyBuf.data());
// If some startup handling is added later, set configured after it was done once.
replies.setConfigured();
// Can be used later to verify correct timing (e.g. all data has been read)
clearReadFlagsDefault(replies);
auto i2cCmdExecMeasure = [&](imtq::CC::CC cc) {
@ -112,18 +121,30 @@ void ImtqPollingTask::handleMeasureStep() {
}
}
// The I2C IP core on EIVE sometimes glitches out. Send start MTM measurement twice.
cmdBuf[0] = imtq::CC::START_MTM_MEASUREMENT;
if (i2cCmdExecMeasure(imtq::CC::START_MTM_MEASUREMENT) != returnvalue::OK) {
return;
}
cmdBuf[0] = imtq::CC::START_MTM_MEASUREMENT;
if (i2cCmdExecMeasure(imtq::CC::START_MTM_MEASUREMENT) != returnvalue::OK) {
return;
}
// Takes a bit of time to take measurements. Subtract a bit because of the delay of previous
// commands.
TaskFactory::delayTask(currentIntegrationTimeMs);
TaskFactory::delayTask(currentIntegrationTimeMs + MGM_READ_BUFFER_TIME_MS);
cmdBuf[0] = imtq::CC::GET_RAW_MTM_MEASUREMENT;
if (i2cCmdExecMeasure(imtq::CC::GET_RAW_MTM_MEASUREMENT) != returnvalue::OK) {
return;
}
bool mgmMeasurementTooOld = false;
// See p.39 of the iMTQ user manual. If the NEW bit of the STAT bitfield is not set, we probably
// have old data. Which can be really bad for ACS. And everything.
if ((replyPtr[2] >> 7) == 0) {
replyPtr[0] = false;
mgmMeasurementTooOld = true;
}
cmdBuf[0] = imtq::CC::GET_ENG_HK_DATA;
if (i2cCmdExecMeasure(imtq::CC::GET_ENG_HK_DATA) != returnvalue::OK) {
@ -134,7 +155,9 @@ void ImtqPollingTask::handleMeasureStep() {
if (i2cCmdExecMeasure(imtq::CC::GET_CAL_MTM_MEASUREMENT) != returnvalue::OK) {
return;
}
// sif::debug << "measure done" << std::endl;
if (mgmMeasurementTooOld) {
sif::error << "IMTQ: MGM measurement too old" << std::endl;
}
return;
}
@ -157,23 +180,41 @@ void ImtqPollingTask::handleActuateStep() {
return;
}
TaskFactory::delayTask(10);
cmdLen = 1;
// The I2C IP core on EIVE sometimes glitches out. Send start MTM measurement twice.
cmdBuf[0] = imtq::CC::START_MTM_MEASUREMENT;
if (i2cCmdExecActuate(imtq::CC::START_MTM_MEASUREMENT) != returnvalue::OK) {
return;
}
cmdBuf[0] = imtq::CC::START_MTM_MEASUREMENT;
if (i2cCmdExecActuate(imtq::CC::START_MTM_MEASUREMENT) != returnvalue::OK) {
return;
}
TaskFactory::delayTask(currentIntegrationTimeMs);
TaskFactory::delayTask(currentIntegrationTimeMs + MGM_READ_BUFFER_TIME_MS);
cmdBuf[0] = imtq::CC::GET_RAW_MTM_MEASUREMENT;
if (i2cCmdExecActuate(imtq::CC::GET_RAW_MTM_MEASUREMENT) != returnvalue::OK) {
return;
}
bool measurementWasTooOld = false;
// See p.39 of the iMTQ user manual. If the NEW bit of the STAT bitfield is not set, we probably
// have old data. Which can be really bad for ACS. And everything.
if ((replyPtr[2] >> 7) == 0) {
measurementWasTooOld = true;
replyPtr[0] = false;
}
cmdBuf[0] = imtq::CC::GET_ENG_HK_DATA;
if (i2cCmdExecActuate(imtq::CC::GET_ENG_HK_DATA) != returnvalue::OK) {
return;
}
// sif::debug << "measure with torque done" << std::endl;
if (measurementWasTooOld) {
sif::error << "IMTQ: MGM measurement too old" << std::endl;
}
return;
}
@ -192,19 +233,19 @@ ReturnValue_t ImtqPollingTask::initializeInterface(CookieIF* cookie) {
ReturnValue_t ImtqPollingTask::sendMessage(CookieIF* cookie, const uint8_t* sendData,
size_t sendLen) {
ImtqRequest request(sendData, sendLen);
const auto* imtqReq = reinterpret_cast<const imtq::Request*>(sendData);
{
MutexGuard mg(ipcLock);
currentRequest = request.getRequestType();
if (currentRequest == imtq::RequestType::ACTUATE) {
std::memcpy(dipoles, request.getDipoles(), 6);
torqueDuration = request.getTorqueDuration();
if (imtqReq->request == imtq::RequestType::ACTUATE) {
std::memcpy(dipoles, imtqReq->dipoles, sizeof(dipoles));
torqueDuration = imtqReq->torqueDuration;
}
specialRequest = request.getSpecialRequest();
currentRequest = imtqReq->request;
specialRequest = imtqReq->specialRequest;
if (state != InternalState::IDLE) {
return returnvalue::FAILED;
}
state = InternalState::BUSY;
state = InternalState::IS_BUSY;
}
semaphore->release();
@ -309,6 +350,8 @@ void ImtqPollingTask::buildDipoleCommand() {
}
SerializeAdapter::serialize(&torqueDuration, &serPtr, &serLen, cmdBuf.size(),
SerializeIF::Endianness::LITTLE);
// sif::debug << "Dipole X: " << dipoles[0] << std::endl;
// sif::debug << "Torqeu Dur: " << torqueDuration << std::endl;
cmdLen = 1 + serLen;
}
@ -325,9 +368,11 @@ ReturnValue_t ImtqPollingTask::readReceivedMessage(CookieIF* cookie, uint8_t** b
if (currentRequest == imtq::RequestType::MEASURE_NO_ACTUATION) {
replyLen = getExchangeBufLen(specialRequest);
memcpy(exchangeBuf.data(), replyBuf.data(), replyLen);
} else {
} else if (currentRequest == imtq::RequestType::ACTUATE) {
replyLen = ImtqRepliesWithTorque::BASE_LEN;
memcpy(exchangeBuf.data(), replyBufActuation.data(), replyLen);
} else {
*size = 0;
}
*buffer = exchangeBuf.data();
*size = replyLen;
@ -383,12 +428,20 @@ ReturnValue_t ImtqPollingTask::performI2cFullRequest(uint8_t* reply, size_t repl
if (ioctl(fd, I2C_SLAVE, i2cAddr) < 0) {
sif::warning << "Opening IMTQ slave device failed with code " << errno << ": "
<< strerror(errno) << std::endl;
if (errno == EBUSY) {
i2cFatalErrors++;
}
}
int written = write(fd, cmdBuf.data(), cmdLen);
if (written < 0) {
sif::error << "IMTQ: Failed to send with error code " << errno
<< ". Error description: " << strerror(errno) << std::endl;
// This is a weird issue which sometimes occurs on debug builds. All I2C buses are busy
// for all writes,
if (errno == EBUSY) {
i2cFatalErrors++;
}
return returnvalue::FAILED;
} else if (static_cast<size_t>(written) != cmdLen) {
sif::error << "IMTQ: Could not write all bytes" << std::endl;

View File

@ -4,6 +4,8 @@
#include <fsfw/tasks/SemaphoreIF.h>
#include <fsfw_hal/linux/i2c/I2cCookie.h>
#include <atomic>
#include "fsfw/devicehandlers/DeviceCommunicationIF.h"
#include "fsfw/objectmanager/SystemObject.h"
#include "fsfw/tasks/ExecutableObjectIF.h"
@ -13,7 +15,7 @@ class ImtqPollingTask : public SystemObject,
public ExecutableObjectIF,
public DeviceCommunicationIF {
public:
ImtqPollingTask(object_id_t imtqPollingTask);
ImtqPollingTask(object_id_t imtqPollingTask, std::atomic_uint16_t& i2cFatalErrors);
ReturnValue_t performOperation(uint8_t operationCode) override;
ReturnValue_t initialize() override;
@ -21,23 +23,25 @@ class ImtqPollingTask : public SystemObject,
private:
static constexpr ReturnValue_t NO_REPLY_AVAILABLE = returnvalue::makeCode(2, 0);
enum class InternalState { IDLE, BUSY } state = InternalState::IDLE;
enum class InternalState { IDLE, IS_BUSY } state = InternalState::IDLE;
imtq::RequestType currentRequest = imtq::RequestType::MEASURE_NO_ACTUATION;
SemaphoreIF* semaphore;
ReturnValue_t comStatus = returnvalue::OK;
MutexIF* ipcLock;
MutexIF* bufLock;
std::atomic_uint16_t& i2cFatalErrors;
I2cCookie* i2cCookie = nullptr;
const char* i2cDev = nullptr;
address_t i2cAddr = 0;
uint32_t currentIntegrationTimeMs = 10;
// Required in addition to integration time, otherwise old data might be read.
static constexpr uint32_t MGM_READ_BUFFER_TIME_MS = 6;
bool ignoreNextActuateRequest = false;
imtq::SpecialRequest specialRequest = imtq::SpecialRequest::NONE;
int16_t dipoles[3] = {};
uint16_t torqueDuration = 0;
// uint8_t startActuateRawBuf[3] = {};
std::array<uint8_t, 32> cmdBuf;
std::array<uint8_t, 524> replyBuf;

View File

@ -19,25 +19,19 @@ static constexpr uint8_t BASE_CFG =
Max31865RtdPolling::Max31865RtdPolling(object_id_t objectId, SpiComIF* lowLevelComIF,
GpioIF* gpioIF)
: SystemObject(objectId), rtds(EiveMax31855::NUM_RTDS), comIF(lowLevelComIF), gpioIF(gpioIF) {
readerMutex = MutexFactory::instance()->createMutex();
readerLock = MutexFactory::instance()->createMutex();
}
ReturnValue_t Max31865RtdPolling::performOperation(uint8_t operationCode) {
using namespace MAX31865;
ReturnValue_t result = returnvalue::OK;
static_cast<void>(result);
// Measured to take 0-1 ms in debug build
// 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 returnvalue::OK;
}
periodicInitHandling();
#if OBSW_RTD_AUTO_MODE == 0
// 10 ms delay for VBIAS startup
TaskFactory::delayTask(10);
result = periodicReadReqHandling();
if (result != returnvalue::OK) {
return result;
@ -56,19 +50,28 @@ bool Max31865RtdPolling::rtdIsActive(uint8_t idx) {
return false;
}
bool Max31865RtdPolling::periodicInitHandling() {
ReturnValue_t Max31865RtdPolling::periodicInitHandling() {
using namespace MAX31865;
ReturnValue_t result = returnvalue::OK;
for (auto& rtd : rtds) {
if (rtd == nullptr) {
continue;
}
MutexGuard mg(readerMutex);
if (mg.getLockResult() != returnvalue::OK) {
sif::warning << "Max31865RtdReader::periodicInitHandling: Mutex lock failed" << std::endl;
return false;
bool mustPerformInitHandling = false;
bool doWriteLowThreshold = false;
bool doWriteHighThreshold = false;
{
MutexGuard mg(readerLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
if (mg.getLockResult() != returnvalue::OK) {
sif::warning << "Max31865RtdReader::periodicInitHandling: Mutex lock failed" << std::endl;
continue;
}
mustPerformInitHandling =
(rtd->on or rtd->db.active) and not rtd->db.configured and rtd->cd.hasTimedOut();
doWriteHighThreshold = rtd->writeHighThreshold;
doWriteLowThreshold = rtd->writeLowThreshold;
}
if ((rtd->on or rtd->db.active) and not rtd->db.configured and rtd->cd.hasTimedOut()) {
if (mustPerformInitHandling) {
// Please note that using the manual CS lock wrapper here is problematic. Might be a SPI
// or hardware specific issue where the CS needs to be pulled high and then low again
// between transfers
@ -77,13 +80,13 @@ bool Max31865RtdPolling::periodicInitHandling() {
handleSpiError(rtd, result, "writeCfgReg");
continue;
}
if (rtd->writeLowThreshold) {
if (doWriteLowThreshold) {
result = writeLowThreshold(rtd->spiCookie, rtd->lowThreshold);
if (result != returnvalue::OK) {
handleSpiError(rtd, result, "writeLowThreshold");
}
}
if (rtd->writeHighThreshold) {
if (doWriteHighThreshold) {
result = writeHighThreshold(rtd->spiCookie, rtd->highThreshold);
if (result != returnvalue::OK) {
handleSpiError(rtd, result, "writeHighThreshold");
@ -93,38 +96,23 @@ bool Max31865RtdPolling::periodicInitHandling() {
if (result != returnvalue::OK) {
handleSpiError(rtd, result, "clearFaultStatus");
}
MutexGuard mg(readerLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
rtd->db.configured = true;
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;
return returnvalue::OK;
}
ReturnValue_t Max31865RtdPolling::periodicReadReqHandling() {
using namespace MAX31865;
updateActiveRtdsArray();
// Now request one shot config for all active RTDs
for (auto& rtd : rtds) {
if (rtd == nullptr) {
continue;
}
MutexGuard mg(readerMutex);
if (mg.getLockResult() != returnvalue::OK) {
sif::warning << "Max31865RtdReader::periodicReadReqHandling: Mutex lock failed" << std::endl;
return returnvalue::FAILED;
}
if (rtdIsActive(rtd->idx)) {
if (activeRtdsArray[rtd->idx]) {
ReturnValue_t result = writeCfgReg(rtd->spiCookie, BASE_CFG | (1 << CfgBitPos::ONE_SHOT));
if (result != returnvalue::OK) {
handleSpiError(rtd, result, "writeCfgReg");
@ -139,17 +127,13 @@ ReturnValue_t Max31865RtdPolling::periodicReadReqHandling() {
ReturnValue_t Max31865RtdPolling::periodicReadHandling() {
using namespace MAX31865;
auto result = returnvalue::OK;
updateActiveRtdsArray();
// Now read the RTD values
for (auto& rtd : rtds) {
if (rtd == nullptr) {
continue;
}
MutexGuard mg(readerMutex);
if (mg.getLockResult() != returnvalue::OK) {
sif::warning << "Max31865RtdReader::periodicReadHandling: Mutex lock failed" << std::endl;
return returnvalue::FAILED;
}
if (rtdIsActive(rtd->idx)) {
if (activeRtdsArray[rtd->idx]) {
// Please note that using the manual CS lock wrapper here is problematic. Might be a SPI
// or hardware specific issue where the CS needs to be pulled high and then low again
// between transfers
@ -166,6 +150,7 @@ ReturnValue_t Max31865RtdPolling::periodicReadHandling() {
handleSpiError(rtd, result, "readRtdVal");
continue;
}
MutexGuard mg(readerLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
if (faultBitSet) {
rtd->db.faultBitSet = faultBitSet;
}
@ -200,7 +185,7 @@ ReturnValue_t Max31865RtdPolling::initializeInterface(CookieIF* cookie) {
throw std::invalid_argument("Invalid RTD index");
}
rtds[rtdCookie->idx] = rtdCookie;
MutexGuard mg(readerMutex);
MutexGuard mg(readerLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
if (dbLen == 0) {
dbLen = rtdCookie->db.getSerializedSize();
}
@ -212,16 +197,19 @@ ReturnValue_t Max31865RtdPolling::sendMessage(CookieIF* cookie, const uint8_t* s
if (cookie == nullptr) {
return returnvalue::FAILED;
}
auto* rtdCookie = dynamic_cast<Max31865ReaderCookie*>(cookie);
if (rtdCookie == nullptr) {
return returnvalue::FAILED;
}
// Empty command.. don't fail for now
if (sendLen < 1) {
return returnvalue::OK;
}
MutexGuard mg(readerMutex);
MutexGuard mg(readerLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
if (mg.getLockResult() != returnvalue::OK) {
sif::warning << "Max31865RtdReader::sendMessage: Mutex lock failed" << std::endl;
return returnvalue::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;
@ -240,7 +228,6 @@ ReturnValue_t Max31865RtdPolling::sendMessage(CookieIF* cookie, const uint8_t* s
case (EiveMax31855::RtdCommands::ON): {
if (not rtdCookie->on) {
rtdCookie->cd.setTimeout(MAX31865::WARMUP_MS);
rtdCookie->cd.resetTimer();
rtdCookie->on = true;
rtdCookie->db.active = false;
rtdCookie->db.configured = false;
@ -253,7 +240,6 @@ ReturnValue_t Max31865RtdPolling::sendMessage(CookieIF* cookie, const uint8_t* s
case (EiveMax31855::RtdCommands::ACTIVE): {
if (not rtdCookie->on) {
rtdCookie->cd.setTimeout(MAX31865::WARMUP_MS);
rtdCookie->cd.resetTimer();
rtdCookie->on = true;
rtdCookie->db.active = true;
rtdCookie->db.configured = false;
@ -312,15 +298,15 @@ ReturnValue_t Max31865RtdPolling::requestReceiveMessage(CookieIF* cookie, size_t
ReturnValue_t Max31865RtdPolling::readReceivedMessage(CookieIF* cookie, uint8_t** buffer,
size_t* size) {
MutexGuard mg(readerMutex);
if (mg.getLockResult() != returnvalue::OK) {
// TODO: Emit warning
return returnvalue::FAILED;
}
auto* rtdCookie = dynamic_cast<Max31865ReaderCookie*>(cookie);
if (rtdCookie == nullptr) {
return returnvalue::FAILED;
}
MutexGuard mg(readerLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
if (mg.getLockResult() != returnvalue::OK) {
// TODO: Emit warning
return returnvalue::FAILED;
}
uint8_t* exchangePtr = rtdCookie->exchangeBuf.data();
size_t serLen = 0;
auto result = rtdCookie->db.serialize(&exchangePtr, &serLen, rtdCookie->exchangeBuf.size(),
@ -461,6 +447,18 @@ ReturnValue_t Max31865RtdPolling::readNFromReg(SpiCookie* cookie, uint8_t reg, s
return returnvalue::OK;
}
ReturnValue_t Max31865RtdPolling::updateActiveRtdsArray() {
MutexGuard mg(readerLock, LOCK_TYPE, LOCK_TIMEOUT, LOCK_CTX);
if (mg.getLockResult() != returnvalue::OK) {
sif::warning << "Max31865RtdReader::periodicReadHandling: Mutex lock failed" << std::endl;
return returnvalue::FAILED;
}
for (const auto& rtd : rtds) {
activeRtdsArray[rtd->idx] = rtdIsActive(rtd->idx);
}
return returnvalue::OK;
}
ReturnValue_t Max31865RtdPolling::handleSpiError(Max31865ReaderCookie* cookie, ReturnValue_t result,
const char* ctx) {
cookie->db.spiErrorCount.value += 1;

View File

@ -47,8 +47,12 @@ class Max31865RtdPolling : public SystemObject,
private:
std::vector<Max31865ReaderCookie*> rtds;
std::array<uint8_t, 4> cmdBuf = {};
std::array<bool, 12> activeRtdsArray{};
size_t dbLen = 0;
MutexIF* readerMutex;
MutexIF* readerLock;
static constexpr MutexIF::TimeoutType LOCK_TYPE = MutexIF::TimeoutType::WAITING;
static constexpr uint32_t LOCK_TIMEOUT = 20;
static constexpr char LOCK_CTX[] = "Max31865RtdPolling";
SpiComIF* comIF;
GpioIF* gpioIF;
@ -56,7 +60,7 @@ class Max31865RtdPolling : public SystemObject,
uint32_t csTimeoutMs = spi::RTD_CS_TIMEOUT;
MutexIF* csLock = nullptr;
bool periodicInitHandling();
ReturnValue_t periodicInitHandling();
ReturnValue_t periodicReadReqHandling();
ReturnValue_t periodicReadHandling();
@ -81,6 +85,8 @@ class Max31865RtdPolling : public SystemObject,
ReturnValue_t requestReceiveMessage(CookieIF* cookie, size_t requestLen) override;
ReturnValue_t readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) override;
ReturnValue_t updateActiveRtdsArray();
ReturnValue_t handleSpiError(Max31865ReaderCookie* cookie, ReturnValue_t result, const char* ctx);
};

View File

@ -147,7 +147,7 @@ ReturnValue_t RwPollingTask::sendMessage(CookieIF* cookie, const uint8_t* sendDa
rwCookie->currentRampTime = rampTime;
rwCookie->specialRequest = specialRequest;
if (state == InternalState::IDLE) {
state = InternalState::BUSY;
state = InternalState::IS_BUSY;
semaphore->release();
}
}
@ -220,7 +220,7 @@ ReturnValue_t RwPollingTask::readNextReply(RwCookie& rwCookie, uint8_t* replyBuf
}
pullCsLow(gpioId, gpioIF);
bool lastByteWasFrameMarker = false;
Countdown cd(3000);
Countdown cd(2000);
size_t readIdx = 0;
while (true) {

View File

@ -41,7 +41,7 @@ class RwPollingTask : public SystemObject, public ExecutableObjectIF, public Dev
ReturnValue_t initialize() override;
private:
enum class InternalState { IDLE, BUSY } state = InternalState::IDLE;
enum class InternalState { IDLE, IS_BUSY } state = InternalState::IDLE;
SemaphoreIF* semaphore;
bool debugMode = false;
bool modeAndSpeedWasSet = false;

View File

@ -98,11 +98,11 @@ ReturnValue_t ScexUartReader::initializeInterface(CookieIF *cookie) {
}
// Setting up UART parameters
tty.c_cflag &= ~PARENB; // Clear parity bit
uart::setStopbits(tty, uartCookie->getStopBits());
uart::setBitsPerWord(tty, BitsPerWord::BITS_8);
serial::setStopbits(tty, uartCookie->getStopBits());
serial::setBitsPerWord(tty, BitsPerWord::BITS_8);
tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control
uart::enableRead(tty);
uart::ignoreCtrlLines(tty);
serial::enableRead(tty);
serial::ignoreCtrlLines(tty);
// Use non-canonical mode and clear echo flag
tty.c_lflag &= ~(ICANON | ECHO);
@ -111,7 +111,7 @@ ReturnValue_t ScexUartReader::initializeInterface(CookieIF *cookie) {
tty.c_cc[VTIME] = 0;
tty.c_cc[VMIN] = 0;
uart::setBaudrate(tty, uartCookie->getBaudrate());
serial::setBaudrate(tty, uartCookie->getBaudrate());
if (tcsetattr(serialPort, TCSANOW, &tty) != 0) {
sif::warning << "ScexUartReader::initializeInterface: tcsetattr call failed with error ["
<< errno << ", " << strerror(errno) << std::endl;
@ -148,8 +148,7 @@ ReturnValue_t ScexUartReader::sendMessage(CookieIF *cookie, const uint8_t *sendD
}
size_t bytesWritten = write(serialPort, cmdbuf.data(), encodedLen);
if (bytesWritten != encodedLen) {
sif::warning << "ScexUartReader::sendMessage: Sending ping command to solar experiment failed"
<< std::endl;
sif::warning << "ScexUartReader::sendMessage: Sending command failed" << std::endl;
return FAILED;
}

View File

@ -77,7 +77,7 @@ ReturnValue_t SusPolling::sendMessage(CookieIF* cookie, const uint8_t* sendData,
susDevs[susIdx].mode = susReq->mode;
}
if (state == InternalState::IDLE) {
state = InternalState::BUSY;
state = InternalState::IS_BUSY;
semaphore->release();
}
return OK;

View File

@ -18,7 +18,7 @@ class SusPolling : public SystemObject, public ExecutableObjectIF, public Device
ReturnValue_t initialize() override;
private:
enum class InternalState { IDLE, BUSY } state = InternalState::IDLE;
enum class InternalState { IDLE, IS_BUSY } state = InternalState::IDLE;
struct SusDev {
SpiCookie* cookie = nullptr;

View File

@ -0,0 +1,209 @@
#include "SyrlinksComHandler.h"
#include <fcntl.h>
#include <fsfw/ipc/MutexGuard.h>
#include <fsfw/tasks/SemaphoreFactory.h>
#include <fsfw/tasks/TaskFactory.h>
#include <fsfw/timemanager/Stopwatch.h>
#include <fsfw_hal/linux/serial/SerialCookie.h>
#include <fsfw_hal/linux/serial/helper.h>
#include <unistd.h>
using namespace returnvalue;
SyrlinksComHandler::SyrlinksComHandler(object_id_t objectId)
: SystemObject(objectId), ringBuf(2048, true) {
lock = MutexFactory::instance()->createMutex();
semaphore = SemaphoreFactory::instance()->createBinarySemaphore();
semaphore->acquire();
}
ReturnValue_t SyrlinksComHandler::performOperation(uint8_t opCode) {
while (true) {
lock->lockMutex();
state = State::SLEEPING;
lock->unlockMutex();
semaphore->acquire();
// Stopwatch watch;
readOneReply();
}
return returnvalue::OK;
}
ReturnValue_t SyrlinksComHandler::initializeInterface(CookieIF *cookie) {
if (cookie == nullptr) {
return returnvalue::FAILED;
}
SerialCookie *serCookie = dynamic_cast<SerialCookie *>(cookie);
if (serCookie == nullptr) {
return DeviceCommunicationIF::INVALID_COOKIE_TYPE;
}
// comCookie = serCookie;
std::string devname = serCookie->getDeviceFile();
/* Get file descriptor */
serialPort = open(devname.c_str(), O_RDWR);
if (serialPort < 0) {
sif::warning << "SyrlinksComHandler: open call failed with error [" << errno << ", "
<< strerror(errno) << std::endl;
return returnvalue::FAILED;
}
// Setting up UART parameters
serial::setStopbits(tty, serCookie->getStopBits());
serial::setParity(tty, serCookie->getParity());
serial::setBitsPerWord(tty, BitsPerWord::BITS_8);
tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control
serial::enableRead(tty);
serial::ignoreCtrlLines(tty);
// Use non-canonical mode and clear echo flag
tty.c_lflag &= ~(ICANON | ECHO);
// Non-blocking mode, use polling
tty.c_cc[VTIME] = 0;
tty.c_cc[VMIN] = 0;
serial::setBaudrate(tty, serCookie->getBaudrate());
if (tcsetattr(serialPort, TCSANOW, &tty) != 0) {
sif::warning << "ScexUartReader::initializeInterface: tcsetattr call failed with error ["
<< errno << ", " << strerror(errno) << std::endl;
}
// Flush received and unread data
tcflush(serialPort, TCIOFLUSH);
return returnvalue::OK;
}
ReturnValue_t SyrlinksComHandler::sendMessage(CookieIF *cookie, const uint8_t *sendData,
size_t sendLen) {
{
MutexGuard mg(lock);
if (state != State::SLEEPING) {
return BUSY;
}
}
serial::flushRxBuf(serialPort);
ssize_t writtenBytes = write(serialPort, sendData, sendLen);
if (writtenBytes != static_cast<ssize_t>(sendLen)) {
sif::warning << "StrComHandler: Sending packet failed" << std::endl;
return returnvalue::FAILED;
}
{
MutexGuard mg(lock);
state = State::ACTIVE;
}
semaphore->release();
return returnvalue::OK;
}
ReturnValue_t SyrlinksComHandler::getSendSuccess(CookieIF *cookie) { return returnvalue::OK; }
ReturnValue_t SyrlinksComHandler::requestReceiveMessage(CookieIF *cookie, size_t requestLen) {
return returnvalue::OK;
}
ReturnValue_t SyrlinksComHandler::handleSerialReception() {
ssize_t bytesRead = read(serialPort, reinterpret_cast<void *>(recBuf.data()),
static_cast<unsigned int>(recBuf.size()));
if (bytesRead == 0) {
return NO_SERIAL_DATA_READ;
} else if (bytesRead < 0) {
sif::warning << "SyrlinksComHandler: read call failed with error [" << errno << ", "
<< strerror(errno) << "]" << std::endl;
return FAILED;
} else if (bytesRead >= static_cast<int>(recBuf.size())) {
sif::error << "SyrlinksComHandler: Receive buffer too small for " << bytesRead << " bytes"
<< std::endl;
return FAILED;
} else if (bytesRead > 0) {
// sif::debug << "Received " << bytesRead << " bytes from the Syrlinks" << std::endl;
// arrayprinter::print(recBuf.data(), bytesRead);
ringBuf.writeData(recBuf.data(), bytesRead);
}
return OK;
}
ReturnValue_t SyrlinksComHandler::readReceivedMessage(CookieIF *cookie, uint8_t **buffer,
size_t *size) {
MutexGuard mg(lock);
if (replyResult != returnvalue::OK) {
ReturnValue_t tmp = replyResult;
replyResult = returnvalue::OK;
return tmp;
}
if (replyLen == 0) {
*size = 0;
return returnvalue::OK;
}
*buffer = ipcBuf.data();
*size = replyLen;
replyLen = 0;
return returnvalue::OK;
}
ReturnValue_t SyrlinksComHandler::readOneReply() {
ReturnValue_t result;
uint32_t nextDelayMs = 1;
replyTimeout.resetTimer();
while (true) {
handleSerialReception();
result = tryReadingOneSyrlinksReply();
if (result == returnvalue::OK) {
return returnvalue::OK;
}
if (replyTimeout.hasTimedOut()) {
{
MutexGuard mg(lock);
replyResult = DeviceCommunicationIF::NO_REPLY_RECEIVED;
}
return returnvalue::FAILED;
}
TaskFactory::delayTask(nextDelayMs);
if (nextDelayMs < 32) {
nextDelayMs *= 2;
}
}
}
ReturnValue_t SyrlinksComHandler::tryReadingOneSyrlinksReply() {
size_t bytesToRead = ringBuf.getAvailableReadData();
if (bytesToRead == 0) {
return NO_PACKET_FOUND;
}
bool startMarkerFound = false;
size_t startIdx = 0;
ringBuf.readData(recBuf.data(), bytesToRead);
for (size_t idx = 0; idx < bytesToRead; idx++) {
if (recBuf[idx] == START_MARKER) {
if (startMarkerFound) {
// Probably lost a packet. Discard broken packet.
sif::warning << "SyrlinksComHandler: Detected 2 consecutive start markers" << std::endl;
ringBuf.deleteData(idx);
} else {
startMarkerFound = true;
startIdx = idx;
}
}
if (recBuf[idx] == END_MARKER) {
if (startMarkerFound) {
{
MutexGuard mg(lock);
replyLen = idx - startIdx + 1;
}
// Copy detected packet to IPC buffer so it can be passed back to the device handler.
if (replyLen > ipcBuf.size()) {
sif::error << "SyrlinksComHandler: Detected reply too large" << std::endl;
ringBuf.deleteData(idx);
return returnvalue::FAILED;
}
// sif::debug << "Detected Syrlinks reply with length " << replyLen << std::endl;
std::memcpy(ipcBuf.data(), recBuf.data() + startIdx, replyLen);
ringBuf.deleteData(idx + 1);
return returnvalue::OK;
} else {
// Probably lost a packet. Discard broken packet.
sif::warning << "SyrlinksComHandler: Detected 2 consecutive end markers" << std::endl;
ringBuf.deleteData(idx + 1);
}
}
}
return NO_PACKET_FOUND;
}

View File

@ -0,0 +1,52 @@
#ifndef LINUX_DEVICES_SYRLINKSCOMHANDLER_H_
#define LINUX_DEVICES_SYRLINKSCOMHANDLER_H_
#include <fsfw/container/SimpleRingBuffer.h>
#include <fsfw/devicehandlers/DeviceCommunicationIF.h>
#include <fsfw/objectmanager/SystemObject.h>
#include <fsfw/tasks/ExecutableObjectIF.h>
#include <fsfw/tasks/SemaphoreIF.h>
#include <termios.h>
class SyrlinksComHandler : public DeviceCommunicationIF,
public ExecutableObjectIF,
public SystemObject {
public:
SyrlinksComHandler(object_id_t objectId);
private:
static constexpr char START_MARKER = '<';
static constexpr char END_MARKER = '>';
//! [EXPORT] : [SKIP]
static constexpr ReturnValue_t NO_SERIAL_DATA_READ = returnvalue::makeCode(2, 0);
static constexpr ReturnValue_t NO_PACKET_FOUND = returnvalue::makeCode(2, 1);
enum class State { SLEEPING, ACTIVE } state = State::SLEEPING;
MutexIF *lock;
SemaphoreIF *semaphore;
int serialPort = 0;
struct termios tty {};
Countdown replyTimeout = Countdown(2000);
std::array<uint8_t, 2048> recBuf{};
SimpleRingBuffer ringBuf;
std::array<uint8_t, 1024> ipcBuf{};
size_t replyLen = 0;
ReturnValue_t replyResult = returnvalue::OK;
ReturnValue_t handleSerialReception();
ReturnValue_t performOperation(uint8_t opCode) override;
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 readOneReply();
ReturnValue_t tryReadingOneSyrlinksReply();
};
#endif /* LINUX_DEVICES_SYRLINKSCOMHANDLER_H_ */

View File

@ -31,6 +31,10 @@ 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;
static const DeviceCommandId_t TC_CAM_TAKE_PIC = 22;
static const DeviceCommandId_t TC_SIMPLEX_SEND_FILE = 23;
static const DeviceCommandId_t TC_DOWNLINK_DATA_MODULATE = 24;
static const DeviceCommandId_t TC_MODE_SNAPSHOT = 25;
// Will reset the sequence count of the OBSW
static const DeviceCommandId_t OBSW_RESET_SEQ_COUNT = 50;
@ -50,14 +54,18 @@ static const uint16_t TC_REPLAY_WRITE_SEQUENCE = 0x112;
static const uint16_t TC_DOWNLINK_PWR_ON = 0x113;
static const uint16_t TC_MEM_WRITE = 0x114;
static const uint16_t TC_MEM_READ = 0x115;
static const uint16_t TC_CAM_TAKE_PIC = 0x116;
static const uint16_t TC_FLASHWRITE = 0x117;
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_MODE_REPLAY = 0x11F;
static const uint16_t TC_MODE_SNAPSHOT = 0x120;
static const uint16_t TC_DOWNLINK_DATA_MODULATE = 0x121;
static const uint16_t TC_DOWNLINK_PWR_OFF = 0x124;
static const uint16_t TC_CAM_CMD_SEND = 0x12C;
static const uint16_t TC_SIMPLEX_SEND_FILE = 0x130;
static const uint16_t TM_MEMORY_READ_REPORT = 0x404;
static const uint16_t ACK_SUCCESS = 0x400;
static const uint16_t ACK_FAILURE = 0x401;
@ -107,8 +115,11 @@ static const size_t MAX_DATA_SIZE = 1016;
static const uint16_t TC_WRITE_SEQ_EXECUTION_DELAY = 80;
// Requires approx. 2 seconds for execution. 8 => 4 seconds
static const uint16_t TC_DOWNLINK_PWR_ON_EXECUTION_DELAY = 8;
static const uint16_t TC_CAM_TAKE_PIC_EXECUTION_DELAY = 20;
static const uint16_t TC_SIMPLEX_SEND_FILE_DELAY = 80;
namespace status_code {
static const uint16_t DEFAULT_ERROR_CODE = 0x1;
static const uint16_t UNKNOWN_APID = 0x5DD;
static const uint16_t INCORRECT_LENGTH = 0x5DE;
static const uint16_t INCORRECT_CRC = 0x5DF;
@ -646,6 +657,90 @@ class TcModeIdle : public TcBase {
: TcBase(params, apid::TC_MODE_IDLE, sequenceCount) {}
};
/**
* @brief Class to build mode idle command
*/
class TcModeSnapshot : public TcBase {
public:
TcModeSnapshot(ploc::SpTcParams params, uint16_t sequenceCount)
: TcBase(params, apid::TC_MODE_SNAPSHOT, sequenceCount) {}
};
/**
* @brief Class to build camera take picture command
*/
class TcCamTakePic : public TcBase {
public:
TcCamTakePic(ploc::SpTcParams params, uint16_t sequenceCount)
: TcBase(params, apid::TC_CAM_TAKE_PIC, sequenceCount) {}
ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override {
if (commandDataLen > MAX_DATA_LENGTH) {
return INVALID_LENGTH;
}
std::string fileName(reinterpret_cast<const char*>(commandData));
if (fileName.size() + sizeof(NULL_TERMINATOR) > MAX_FILENAME_SIZE) {
return FILENAME_TOO_LONG;
}
if (commandDataLen - (fileName.size() + sizeof(NULL_TERMINATOR)) != PARAMETER_SIZE) {
return INVALID_LENGTH;
}
spParams.setFullPayloadLen(commandDataLen + CRC_SIZE);
std::memcpy(payloadStart, commandData, commandDataLen);
return returnvalue::OK;
}
private:
static const size_t MAX_DATA_LENGTH = 286;
static const size_t PARAMETER_SIZE = 28;
};
/**
* @brief Class to build simplex send file command
*/
class TcSimplexSendFile : public TcBase {
public:
TcSimplexSendFile(ploc::SpTcParams params, uint16_t sequenceCount)
: TcBase(params, apid::TC_SIMPLEX_SEND_FILE, sequenceCount) {}
ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override {
if (commandDataLen > MAX_DATA_LENGTH) {
return INVALID_LENGTH;
}
std::string fileName(reinterpret_cast<const char*>(commandData));
if (fileName.size() + sizeof(NULL_TERMINATOR) > MAX_FILENAME_SIZE) {
return FILENAME_TOO_LONG;
}
spParams.setFullPayloadLen(commandDataLen + CRC_SIZE);
std::memcpy(payloadStart, commandData, commandDataLen);
return returnvalue::OK;
}
private:
static const size_t MAX_DATA_LENGTH = 256;
};
/**
* @brief Class to build downlink data modulate command
*/
class TcDownlinkDataModulate : public TcBase {
public:
TcDownlinkDataModulate(ploc::SpTcParams params, uint16_t sequenceCount)
: TcBase(params, apid::TC_DOWNLINK_DATA_MODULATE, sequenceCount) {}
ReturnValue_t initPacket(const uint8_t* commandData, size_t commandDataLen) override {
if (commandDataLen > MAX_DATA_LENGTH) {
return INVALID_LENGTH;
}
spParams.setFullPayloadLen(commandDataLen + CRC_SIZE);
std::memcpy(payloadStart, commandData, commandDataLen);
return returnvalue::OK;
}
private:
static const size_t MAX_DATA_LENGTH = 11;
};
class TcCamcmdSend : public TcBase {
public:
TcCamcmdSend(ploc::SpTcParams params, uint16_t sequenceCount)

View File

@ -1,5 +1,7 @@
#include "PlocMPSoCHandler.h"
#include <sstream>
#include "OBSWConfig.h"
#include "fsfw/datapool/PoolReadGuard.h"
#include "fsfw/globalfunctions/CRC.h"
@ -257,6 +259,22 @@ ReturnValue_t PlocMPSoCHandler::buildCommandFromCommand(DeviceCommandId_t device
result = prepareTcCamCmdSend(commandData, commandDataLen);
break;
}
case (mpsoc::TC_CAM_TAKE_PIC): {
result = prepareTcCamTakePic(commandData, commandDataLen);
break;
}
case (mpsoc::TC_SIMPLEX_SEND_FILE): {
result = prepareTcSimplexSendFile(commandData, commandDataLen);
break;
}
case (mpsoc::TC_DOWNLINK_DATA_MODULATE): {
result = prepareTcDownlinkDataModulate(commandData, commandDataLen);
break;
}
case (mpsoc::TC_MODE_SNAPSHOT): {
result = prepareTcModeSnapshot();
break;
}
default:
sif::debug << "PlocMPSoCHandler::buildCommandFromCommand: Command not implemented"
<< std::endl;
@ -288,6 +306,10 @@ void PlocMPSoCHandler::fillCommandAndReplyMap() {
this->insertInCommandMap(mpsoc::TC_CAM_CMD_SEND);
this->insertInCommandMap(mpsoc::RELEASE_UART_TX);
this->insertInCommandMap(mpsoc::SET_UART_TX_TRISTATE);
this->insertInCommandMap(mpsoc::TC_CAM_TAKE_PIC);
this->insertInCommandMap(mpsoc::TC_SIMPLEX_SEND_FILE);
this->insertInCommandMap(mpsoc::TC_DOWNLINK_DATA_MODULATE);
this->insertInCommandMap(mpsoc::TC_MODE_SNAPSHOT);
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);
@ -537,6 +559,53 @@ ReturnValue_t PlocMPSoCHandler::prepareTcCamCmdSend(const uint8_t* commandData,
return returnvalue::OK;
}
ReturnValue_t PlocMPSoCHandler::prepareTcCamTakePic(const uint8_t* commandData,
size_t commandDataLen) {
ReturnValue_t result = returnvalue::OK;
mpsoc::TcCamTakePic tcCamTakePic(spParams, sequenceCount);
result = tcCamTakePic.buildPacket(commandData, commandDataLen);
if (result != returnvalue::OK) {
return result;
}
finishTcPrep(tcCamTakePic.getFullPacketLen());
return returnvalue::OK;
}
ReturnValue_t PlocMPSoCHandler::prepareTcSimplexSendFile(const uint8_t* commandData,
size_t commandDataLen) {
ReturnValue_t result = returnvalue::OK;
mpsoc::TcSimplexSendFile tcSimplexSendFile(spParams, sequenceCount);
result = tcSimplexSendFile.buildPacket(commandData, commandDataLen);
if (result != returnvalue::OK) {
return result;
}
finishTcPrep(tcSimplexSendFile.getFullPacketLen());
return returnvalue::OK;
}
ReturnValue_t PlocMPSoCHandler::prepareTcDownlinkDataModulate(const uint8_t* commandData,
size_t commandDataLen) {
ReturnValue_t result = returnvalue::OK;
mpsoc::TcDownlinkDataModulate tcDownlinkDataModulate(spParams, sequenceCount);
result = tcDownlinkDataModulate.buildPacket(commandData, commandDataLen);
if (result != returnvalue::OK) {
return result;
}
finishTcPrep(tcDownlinkDataModulate.getFullPacketLen());
return returnvalue::OK;
}
ReturnValue_t PlocMPSoCHandler::prepareTcModeSnapshot() {
ReturnValue_t result = returnvalue::OK;
mpsoc::TcModeSnapshot tcModeSnapshot(spParams, sequenceCount);
result = tcModeSnapshot.buildPacket();
if (result != returnvalue::OK) {
return result;
}
finishTcPrep(tcModeSnapshot.getFullPacketLen());
return returnvalue::OK;
}
void PlocMPSoCHandler::finishTcPrep(size_t packetLen) {
nextReplyId = mpsoc::ACK_REPORT;
rawPacket = commandBuffer;
@ -694,6 +763,10 @@ ReturnValue_t PlocMPSoCHandler::enableReplyInReplyMap(DeviceCommandMap::iterator
case mpsoc::TC_REPLAY_WRITE_SEQUENCE:
case mpsoc::TC_MODE_REPLAY:
case mpsoc::TC_MODE_IDLE:
case mpsoc::TC_CAM_TAKE_PIC:
case mpsoc::TC_SIMPLEX_SEND_FILE:
case mpsoc::TC_DOWNLINK_DATA_MODULATE:
case mpsoc::TC_MODE_SNAPSHOT:
enabledReplies = 2;
break;
case mpsoc::TC_MEM_READ: {
@ -753,8 +826,17 @@ ReturnValue_t PlocMPSoCHandler::enableReplyInReplyMap(DeviceCommandMap::iterator
}
case mpsoc::TC_DOWNLINK_PWR_ON: {
DeviceReplyIter iter = deviceReplyMap.find(mpsoc::EXE_REPORT);
//
iter->second.delayCycles = mpsoc::TC_DOWNLINK_PWR_ON;
iter->second.delayCycles = mpsoc::TC_DOWNLINK_PWR_ON_EXECUTION_DELAY;
break;
}
case mpsoc::TC_CAM_TAKE_PIC: {
DeviceReplyIter iter = deviceReplyMap.find(mpsoc::EXE_REPORT);
iter->second.delayCycles = mpsoc::TC_CAM_TAKE_PIC_EXECUTION_DELAY;
break;
}
case mpsoc::TC_SIMPLEX_SEND_FILE: {
DeviceReplyIter iter = deviceReplyMap.find(mpsoc::EXE_REPORT);
iter->second.delayCycles = mpsoc::TC_SIMPLEX_SEND_FILE_DELAY;
break;
}
default:
@ -917,6 +999,18 @@ void PlocMPSoCHandler::disableAllReplies() {
/* If the command expects a telemetry packet the appropriate tm reply will be disabled here */
switch (commandId) {
case TC_MEM_WRITE:
case TC_FLASHDELETE:
case TC_REPLAY_START:
case TC_REPLAY_STOP:
case TC_DOWNLINK_PWR_ON:
case TC_DOWNLINK_PWR_OFF:
case TC_REPLAY_WRITE_SEQUENCE:
case TC_MODE_REPLAY:
case TC_MODE_IDLE:
case TC_CAM_TAKE_PIC:
case TC_SIMPLEX_SEND_FILE:
case TC_DOWNLINK_DATA_MODULATE:
case TC_MODE_SNAPSHOT:
break;
case TC_MEM_READ: {
iter = deviceReplyMap.find(TM_MEMORY_READ_REPORT);
@ -1048,6 +1142,10 @@ std::string PlocMPSoCHandler::getStatusString(uint16_t status) {
return "Flash file already closed";
break;
}
case (mpsoc::status_code::FLASH_FILE_OPEN_FAILED): {
return "Flash file open failed";
break;
}
case (mpsoc::status_code::FLASH_FILE_NOT_OPEN): {
return "Flash file not open";
break;
@ -1084,7 +1182,14 @@ std::string PlocMPSoCHandler::getStatusString(uint16_t status) {
return "Flash uncorrectable mismatch";
break;
}
case (mpsoc::status_code::DEFAULT_ERROR_CODE): {
return "Default error code";
break;
}
default:
std::stringstream ss;
ss << "0x" << std::hex << status;
return ss.str();
break;
}
return "";

View File

@ -169,6 +169,10 @@ class PlocMPSoCHandler : public DeviceHandlerBase, public CommandsActionsIF {
ReturnValue_t prepareTcReplayWriteSequence(const uint8_t* commandData, size_t commandDataLen);
ReturnValue_t prepareTcCamCmdSend(const uint8_t* commandData, size_t commandDataLen);
ReturnValue_t prepareTcModeIdle();
ReturnValue_t prepareTcCamTakePic(const uint8_t* commandData, size_t commandDataLen);
ReturnValue_t prepareTcSimplexSendFile(const uint8_t* commandData, size_t commandDataLen);
ReturnValue_t prepareTcDownlinkDataModulate(const uint8_t* commandData, size_t commandDataLen);
ReturnValue_t prepareTcModeSnapshot();
void finishTcPrep(size_t packetLen);
/**

View File

@ -58,12 +58,12 @@ ReturnValue_t PlocSupvUartManager::initializeInterface(CookieIF* cookie) {
}
// Setting up UART parameters
tty.c_cflag &= ~PARENB; // Clear parity bit
uart::setParity(tty, uartCookie->getParity());
uart::setStopbits(tty, uartCookie->getStopBits());
uart::setBitsPerWord(tty, BitsPerWord::BITS_8);
serial::setParity(tty, uartCookie->getParity());
serial::setStopbits(tty, uartCookie->getStopBits());
serial::setBitsPerWord(tty, BitsPerWord::BITS_8);
tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control
uart::enableRead(tty);
uart::ignoreCtrlLines(tty);
serial::enableRead(tty);
serial::ignoreCtrlLines(tty);
// Use non-canonical mode and clear echo flag
tty.c_lflag &= ~(ICANON | ECHO);
@ -72,7 +72,7 @@ ReturnValue_t PlocSupvUartManager::initializeInterface(CookieIF* cookie) {
tty.c_cc[VTIME] = 2;
tty.c_cc[VMIN] = 0;
uart::setBaudrate(tty, uartCookie->getBaudrate());
serial::setBaudrate(tty, uartCookie->getBaudrate());
if (tcsetattr(serialPort, TCSANOW, &tty) != 0) {
sif::warning << "PlocSupvUartManager::initializeInterface: tcsetattr call failed with error ["
<< errno << ", " << strerror(errno) << std::endl;

View File

@ -246,9 +246,9 @@ class PlocSupvUartManager : public DeviceCommunicationIF,
std::array<uint8_t, 2048> recBuf = {};
std::array<uint8_t, 2048> encodedBuf = {};
std::array<uint8_t, 1200> decodedBuf = {};
std::array<uint8_t, 1200> ipcBuffer = {};
SimpleRingBuffer decodedRingBuf;
FIFO<size_t, MAX_STORED_DECODED_PACKETS> decodedQueue;
std::array<uint8_t, 1200> ipcBuffer = {};
SimpleRingBuffer ipcRingBuf;
FIFO<size_t, MAX_STORED_DECODED_PACKETS> ipcQueue;

View File

@ -1,39 +1,39 @@
#include "ArcsecDatalinkLayer.h"
ArcsecDatalinkLayer::ArcsecDatalinkLayer() { slipInit(); }
ArcsecDatalinkLayer::ArcsecDatalinkLayer() : decodeRingBuf(BUFFER_LENGTHS, true) { slipInit(); }
ArcsecDatalinkLayer::~ArcsecDatalinkLayer() {}
void ArcsecDatalinkLayer::slipInit() {
slipInfo.buffer = rxBuffer;
slipInfo.maxlength = startracker::MAX_FRAME_SIZE;
slipInfo.length = 0;
slipInfo.unescape_next = 0;
slipInfo.prev_state = SLIP_COMPLETE;
}
ReturnValue_t ArcsecDatalinkLayer::decodeFrame(const uint8_t* rawData, size_t rawDataSize,
size_t* bytesLeft) {
size_t bytePos = 0;
for (bytePos = 0; bytePos < rawDataSize; bytePos++) {
ReturnValue_t ArcsecDatalinkLayer::checkRingBufForFrame(const uint8_t** decodedFrame,
size_t& frameLen) {
size_t currentLen = decodeRingBuf.getAvailableReadData();
if (currentLen == 0) {
return DEC_IN_PROGRESS;
}
decodeRingBuf.readData(rxAnalysisBuffer, currentLen);
for (size_t idx = 0; idx < currentLen; idx++) {
enum arc_dec_result decResult =
arc_transport_decode_body(*(rawData + bytePos), &slipInfo, decodedFrame, &decFrameSize);
*bytesLeft = rawDataSize - bytePos - 1;
arc_transport_decode_body(rxAnalysisBuffer[idx], &slipInfo, decodedRxFrame, &rxFrameSize);
switch (decResult) {
case ARC_DEC_INPROGRESS: {
if (bytePos == rawDataSize - 1) {
return DEC_IN_PROGRESS;
}
continue;
break;
}
case ARC_DEC_ERROR_FRAME_SHORT:
case ARC_DEC_ERROR_FRAME_SHORT: {
decodeRingBuf.deleteData(idx);
return REPLY_TOO_SHORT;
}
case ARC_DEC_ERROR_CHECKSUM:
decodeRingBuf.deleteData(idx);
return CRC_FAILURE;
case ARC_DEC_ASYNC:
case ARC_DEC_SYNC: {
// Reset length of SLIP struct for next frame
slipInfo.length = 0;
if (decodedFrame != nullptr) {
*decodedFrame = decodedRxFrame;
}
frameLen = rxFrameSize;
decodeRingBuf.deleteData(idx);
return returnvalue::OK;
}
default:
@ -42,21 +42,32 @@ ReturnValue_t ArcsecDatalinkLayer::decodeFrame(const uint8_t* rawData, size_t ra
return returnvalue::FAILED;
}
}
return returnvalue::FAILED;
decodeRingBuf.deleteData(currentLen);
return DEC_IN_PROGRESS;
}
uint8_t ArcsecDatalinkLayer::getReplyFrameType() { return decodedFrame[0]; }
const uint8_t* ArcsecDatalinkLayer::getReply() { return &decodedFrame[1]; }
void ArcsecDatalinkLayer::encodeFrame(const uint8_t* data, uint32_t length) {
arc_transport_encode_body(data, length, encBuffer, &encFrameSize);
ReturnValue_t ArcsecDatalinkLayer::feedData(const uint8_t* rawData, size_t rawDataLen) {
if (rawDataLen > 4096) {
sif::error << "ArcsecDatalinklayer: Can not write more than 4096 bytes to ring buffer"
<< std::endl;
return returnvalue::FAILED;
}
return decodeRingBuf.writeData(rawData, rawDataLen);
}
uint8_t* ArcsecDatalinkLayer::getEncodedFrame() { return encBuffer; }
void ArcsecDatalinkLayer::reset() {
slipInit();
decodeRingBuf.clear();
}
uint32_t ArcsecDatalinkLayer::getEncodedLength() { return encFrameSize; }
void ArcsecDatalinkLayer::slipInit() {
slip_decode_init(rxBufferArc, sizeof(rxBufferArc), &slipInfo);
}
uint8_t ArcsecDatalinkLayer::getStatusField() { return *(decodedFrame + STATUS_OFFSET); }
uint8_t ArcsecDatalinkLayer::getId() { return *(decodedFrame + ID_OFFSET); }
void ArcsecDatalinkLayer::encodeFrame(const uint8_t* data, size_t length, const uint8_t** txFrame,
size_t& size) {
arc_transport_encode_body(data, length, txEncoded, &size);
if (txFrame != nullptr) {
*txFrame = txEncoded;
}
}

View File

@ -1,14 +1,14 @@
#ifndef BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_
#define BSP_Q7S_DEVICES_ARCSECDATALINKLAYER_H_
#include <fsfw/container/SimpleRingBuffer.h>
#include <fsfw/devicehandlers/CookieIF.h>
#include "arcsec/common/misc.h"
#include "eive/resultClassIds.h"
#include "fsfw/returnvalues/returnvalue.h"
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
extern "C" {
#include "common/misc.h"
}
/**
* @brief Helper class to handle the datalinklayer of replies from the star tracker of arcsec.
*/
@ -25,17 +25,30 @@ class ArcsecDatalinkLayer {
static const uint8_t STATUS_OK = 0;
static constexpr size_t BUFFER_LENGTHS = 4096;
ArcsecDatalinkLayer();
virtual ~ArcsecDatalinkLayer();
/**
* @brief Applies decoding to data referenced by rawData pointer
*
* @param rawData Pointer to raw data received from star tracker
* @param rawDataSize Size of raw data stream
* @param remainingBytes Number of bytes left
* Feed received data to the internal ring buffer.
* @param rawData
* @param rawDataLen
* @return
*/
ReturnValue_t decodeFrame(const uint8_t* rawData, size_t rawDataSize, size_t* bytesLeft);
ReturnValue_t feedData(const uint8_t* rawData, size_t rawDataLen);
/**
* Runs the arcsec datalink layer decoding algorithm on the data in the ring buffer, decoding
* frames in the process.
* @param decodedFrame
* @param frameLen
* @return
* - returnvalue::OK if a frame was found
* - DEC_IN_PROGRESS if frame decoding is in progress
* - Anything else is a decoding error
*/
ReturnValue_t checkRingBufForFrame(const uint8_t** decodedFrame, size_t& frameLen);
/**
* @brief SLIP encodes data pointed to by data pointer.
@ -43,53 +56,31 @@ class ArcsecDatalinkLayer {
* @param data Pointer to data to encode
* @param length Length of buffer to encode
*/
void encodeFrame(const uint8_t* data, uint32_t length);
void encodeFrame(const uint8_t* data, size_t length, const uint8_t** txFrame, size_t& frameLen);
/**
* @brief Returns the frame type field of a decoded frame.
*/
uint8_t getReplyFrameType();
/**
* @brief Returns pointer to reply packet (first entry normally action ID, telemetry ID etc.)
*/
const uint8_t* getReply();
/**
* @brief Returns size of encoded frame
*/
uint32_t getEncodedLength();
/**
* @brief Returns pointer to encoded frame
*/
uint8_t* getEncodedFrame();
/**
* @brief Returns status of reply
*/
uint8_t getStatusField();
/**
* @brief Returns ID of reply
*/
uint8_t getId();
void reset();
private:
static const uint8_t ID_OFFSET = 1;
static const uint8_t STATUS_OFFSET = 2;
// Used by arcsec slip decoding function process received data
uint8_t rxBuffer[startracker::MAX_FRAME_SIZE];
// User to buffer and analyse data and allow feeding and checking for frames asychronously.
SimpleRingBuffer decodeRingBuf;
uint8_t rxAnalysisBuffer[BUFFER_LENGTHS];
// Used by arcsec slip decoding function to process received data. This should only be written
// to or read from by arcsec functions!
uint8_t rxBufferArc[startracker::MAX_FRAME_SIZE];
// Decoded frame will be copied to this buffer
uint8_t decodedFrame[startracker::MAX_FRAME_SIZE];
uint8_t decodedRxFrame[startracker::MAX_FRAME_SIZE];
// Size of decoded frame
uint32_t rxFrameSize = 0;
// Buffer where encoded frames will be stored. First byte of encoded frame represents type of
// reply
uint8_t encBuffer[startracker::MAX_FRAME_SIZE * 2 + 2];
// Size of decoded frame
uint32_t decFrameSize = 0;
uint8_t txEncoded[startracker::MAX_FRAME_SIZE * 2 + 2];
// Size of encoded frame
uint32_t encFrameSize = 0;
uint32_t txFrameSize = 0;
slip_decode_state slipInfo;

View File

@ -1,18 +1,11 @@
#include "ArcsecJsonParamBase.h"
#include "ArcsecJsonKeys.h"
#include "arcsecJsonKeys.h"
ArcsecJsonParamBase::ArcsecJsonParamBase(std::string setName) : setName(setName) {}
ReturnValue_t ArcsecJsonParamBase::create(std::string fullname, uint8_t* buffer) {
ReturnValue_t result = returnvalue::OK;
result = init(fullname);
if (result != returnvalue::OK) {
sif::warning << "ArcsecJsonParamBase::create: Failed to init parameter command for set "
<< setName << std::endl;
return result;
}
result = createCommand(buffer);
ReturnValue_t ArcsecJsonParamBase::create(uint8_t* buffer) {
ReturnValue_t result = createCommand(buffer);
if (result != returnvalue::OK) {
sif::warning << "ArcsecJsonParamBase::create: Failed to create parameter command for set "
<< setName << std::endl;
@ -74,12 +67,17 @@ ReturnValue_t ArcsecJsonParamBase::init(const std::string filename) {
<< std::endl;
return JSON_FILE_NOT_EXISTS;
}
createJsonObject(filename);
result = initSet();
if (result != returnvalue::OK) {
return result;
try {
createJsonObject(filename);
result = initSet();
if (result != returnvalue::OK) {
return result;
}
return returnvalue::OK;
} catch (json::exception& e) {
// TODO: Re-create json file from backup here.
return returnvalue::FAILED;
}
return returnvalue::OK;
}
void ArcsecJsonParamBase::createJsonObject(const std::string fullname) {

View File

@ -5,15 +5,12 @@
#include <fstream>
#include <nlohmann/json.hpp>
#include "arcsec/common/generated/tmtcstructs.h"
#include "arcsec/common/genericstructs.h"
#include "eive/resultClassIds.h"
#include "fsfw/returnvalues/returnvalue.h"
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
extern "C" {
#include "thirdparty/arcsec_star_tracker/common/generated/tmtcstructs.h"
#include "thirdparty/arcsec_star_tracker/common/genericstructs.h"
}
using json = nlohmann::json;
/**
@ -41,6 +38,17 @@ class ArcsecJsonParamBase {
*/
ArcsecJsonParamBase(std::string setName);
/**
* @brief Initializes the properties json object and the set json object
*
* @param fullname Name including absolute path to json file
* @param setName The name of the set to work on
*
* @param return JSON_FILE_NOT_EXISTS if specified file does not exist, otherwise
* returnvalue::OK
*/
ReturnValue_t init(const std::string filename);
/**
* @brief Fills a buffer with a parameter set
*
@ -48,7 +56,7 @@ class ArcsecJsonParamBase {
* parameter set.
* @param buffer Pointer to the buffer the command will be written to
*/
ReturnValue_t create(std::string fullname, uint8_t* buffer);
ReturnValue_t create(uint8_t* buffer);
/**
* @brief Returns the size of the parameter command.
@ -124,17 +132,6 @@ class ArcsecJsonParamBase {
*/
virtual ReturnValue_t createCommand(uint8_t* buffer) = 0;
/**
* @brief Initializes the properties json object and the set json object
*
* @param fullname Name including absolute path to json file
* @param setName The name of the set to work on
*
* @param return JSON_FILE_NOT_EXISTS if specified file does not exist, otherwise
* returnvalue::OK
*/
ReturnValue_t init(const std::string filename);
void createJsonObject(const std::string fullname);
/**

View File

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

File diff suppressed because it is too large Load Diff

View File

@ -3,16 +3,18 @@
#include <fsfw/datapool/PoolReadGuard.h>
#include "ArcsecDatalinkLayer.h"
#include <thread>
#include "ArcsecJsonParamBase.h"
#include "OBSWConfig.h"
#include "StrHelper.h"
#include "StrComHandler.h"
#include "arcsec/common/SLIP.h"
#include "devices/powerSwitcherList.h"
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
#include "fsfw/src/fsfw/serialize/SerializeAdapter.h"
#include "fsfw/timemanager/Countdown.h"
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
#include "thirdparty/arcsec_star_tracker/common/SLIP.h"
#include "strJsonCommands.h"
/**
* @brief This is the device handler for the star tracker from arcsec.
@ -35,7 +37,8 @@ class StarTrackerHandler : public DeviceHandlerBase {
* to high to enable the device.
*/
StarTrackerHandler(object_id_t objectId, object_id_t comIF, CookieIF* comCookie,
StrHelper* strHelper, power::Switch_t powerSwitch);
const char* jsonFileStr, StrComHandler* strHelper,
power::Switch_t powerSwitch);
virtual ~StarTrackerHandler();
ReturnValue_t initialize() override;
@ -57,7 +60,6 @@ class StarTrackerHandler : public DeviceHandlerBase {
protected:
void doStartUp() override;
void doShutDown() override;
void doOffActivity() override;
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t* id) override;
ReturnValue_t buildTransitionDeviceCommand(DeviceCommandId_t* id) override;
void fillCommandAndReplyMap() override;
@ -130,12 +132,10 @@ class StarTrackerHandler : public DeviceHandlerBase {
static const ReturnValue_t STR_HELPER_EXECUTING = MAKE_RETURN_CODE(0xB5);
//! [EXPORT] : [COMMENT] Star tracker is already in firmware mode
static const ReturnValue_t STARTRACKER_ALREADY_BOOTED = MAKE_RETURN_CODE(0xB6);
//! [EXPORT] : [COMMENT] Star tracker is in firmware mode but must be in bootloader mode to
//! execute this command
static const ReturnValue_t STARTRACKER_RUNNING_FIRMWARE = MAKE_RETURN_CODE(0xB7);
//! [EXPORT] : [COMMENT] Star tracker is in bootloader mode but must be in firmware mode to
//! execute this command
static const ReturnValue_t STARTRACKER_RUNNING_BOOTLOADER = MAKE_RETURN_CODE(0xB8);
//! [EXPORT] : [COMMENT] Star tracker must be in firmware mode to run this command
static const ReturnValue_t STARTRACKER_NOT_RUNNING_FIRMWARE = MAKE_RETURN_CODE(0xB7);
//! [EXPORT] : [COMMENT] Star tracker must be in bootloader mode to run this command
static const ReturnValue_t STARTRACKER_NOT_RUNNING_BOOTLOADER = MAKE_RETURN_CODE(0xB8);
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::STR_HANDLER;
@ -147,14 +147,14 @@ class StarTrackerHandler : public DeviceHandlerBase {
static const size_t MAX_PATH_SIZE = 50;
static const size_t MAX_FILE_NAME = 30;
static const uint8_t STATUS_OFFSET = 1;
static const uint8_t PARAMS_OFFSET = 1;
static const uint8_t TICKS_OFFSET = 2;
static const uint8_t TIME_OFFSET = 6;
static const uint8_t TM_DATA_FIELD_OFFSET = 14;
static const uint8_t PARAMETER_ID_OFFSET = 0;
static const uint8_t ACTION_ID_OFFSET = 0;
static const uint8_t ACTION_DATA_OFFSET = 2;
static const uint8_t STATUS_OFFSET = 2;
static const uint8_t PARAMS_OFFSET = 2;
static const uint8_t TICKS_OFFSET = 3;
static const uint8_t TIME_OFFSET = 7;
static const uint8_t PARAMETER_ID_OFFSET = 1;
static const uint8_t ACTION_ID_OFFSET = 1;
static const uint8_t ACTION_DATA_OFFSET = 3;
// Ping request will reply ping with this ID (data field)
static const uint32_t PING_ID = 0x55;
static const uint32_t BOOT_REGION_ID = 1;
@ -182,8 +182,6 @@ class StarTrackerHandler : public DeviceHandlerBase {
MessageQueueIF* eventQueue = nullptr;
ArcsecDatalinkLayer dataLinkLayer;
startracker::TemperatureSet temperatureSet;
startracker::VersionSet versionSet;
startracker::PowerSet powerSet;
@ -208,7 +206,7 @@ class StarTrackerHandler : public DeviceHandlerBase {
startracker::DebugCameraSet debugCameraSet;
// Pointer to object responsible for uploading and downloading images to/from the star tracker
StrHelper* strHelper = nullptr;
StrComHandler* strHelper = nullptr;
uint8_t commandBuffer[startracker::MAX_FRAME_SIZE];
@ -216,28 +214,59 @@ class StarTrackerHandler : public DeviceHandlerBase {
// Loading firmware requires some time and the command will not trigger a reply when executed
Countdown bootCountdown;
#ifdef EGSE
std::string paramJsonFile = "/home/pi/arcsec/json/flight-config.json";
#else
#if OBSW_STAR_TRACKER_GROUND_CONFIG == 1
std::string paramJsonFile = "/mnt/sd0/startracker/ground-config.json";
#else
std::string paramJsonFile = "/mnt/sd0/startracker/flight-config.json";
#endif
#endif
struct JsonConfigs {
Tracking tracking;
LogLevel logLevel;
LogSubscription logSubscription;
DebugCamera debugCamera;
Algo algo;
Validation validation;
Matching matching;
Lisa lisa;
Centroiding centroiding;
Camera camera;
ImageProcessor imageProcessor;
Mounting mounting;
Limits limits;
Subscription subscription;
};
JsonConfigs jcfgs;
Countdown jcfgCountdown = Countdown(250);
bool commandExecuted = false;
std::thread jsonCfgTask;
static void setUpJsonCfgs(JsonConfigs& cfgs, const char* paramJsonFile);
std::string paramJsonFile;
enum class NormalState { TEMPERATURE_REQUEST, SOLUTION_REQUEST };
NormalState normalState = NormalState::TEMPERATURE_REQUEST;
enum class StartupState {
IDLE,
CHECK_PROGRAM,
WAIT_CHECK_PROGRAM,
BOOT_BOOTLOADER,
WAIT_JCFG,
DONE
};
StartupState startupState = StartupState::IDLE;
enum class InternalState {
IDLE,
BOOT,
BOOT_FIRMWARE,
DONE,
FAILED_FIRMWARE_BOOT,
BOOT_BOOTLOADER,
BOOTLOADER_CHECK,
FAILED_BOOTLOADER_BOOT
};
enum class FwBootState {
NONE,
BOOT_DELAY,
REQ_VERSION,
VERIFY_BOOT,
STARTUP_CHECK,
BOOT_DELAY,
FIRMWARE_CHECK,
LOGLEVEL,
LIMITS,
TRACKING,
@ -253,20 +282,12 @@ class StarTrackerHandler : public DeviceHandlerBase {
LOG_SUBSCRIPTION,
DEBUG_CAMERA,
WAIT_FOR_EXECUTION,
DONE,
FAILED_FIRMWARE_BOOT,
BOOT_BOOTLOADER,
BOOTLOADER_CHECK,
BOOTING_BOOTLOADER_FAILED
};
FwBootState bootState = FwBootState::NONE;
InternalState internalState = InternalState::IDLE;
enum class StartupState { IDLE, CHECK_PROGRAM, WAIT_CHECK_PROGRAM, BOOT_BOOTLOADER, DONE };
StartupState startupState = StartupState::IDLE;
bool strHelperExecuting = false;
bool strHelperHandlingSpecialRequest = false;
const power::Switch_t powerSwitch = power::NO_SWITCH;
@ -287,10 +308,10 @@ class StarTrackerHandler : public DeviceHandlerBase {
*/
void slipInit();
ReturnValue_t scanForActionReply(DeviceCommandId_t* foundId);
ReturnValue_t scanForSetParameterReply(DeviceCommandId_t* foundId);
ReturnValue_t scanForGetParameterReply(DeviceCommandId_t* foundId);
ReturnValue_t scanForTmReply(DeviceCommandId_t* foundId);
ReturnValue_t scanForActionReply(uint8_t replyId, DeviceCommandId_t* foundId);
ReturnValue_t scanForSetParameterReply(uint8_t replyId, DeviceCommandId_t* foundId);
ReturnValue_t scanForGetParameterReply(uint8_t replyId, DeviceCommandId_t* foundId);
ReturnValue_t scanForTmReply(uint8_t replyId, DeviceCommandId_t* foundId);
/**
* @brief Fills command buffer with data to ping the star tracker
@ -412,12 +433,13 @@ class StarTrackerHandler : public DeviceHandlerBase {
/**
* @brief Handles action replies with datasets.
*/
ReturnValue_t handleActionReplySet(LocalPoolDataSetBase& dataset, size_t size);
ReturnValue_t handleActionReplySet(const uint8_t* rawFrame, LocalPoolDataSetBase& dataset,
size_t size);
/**
* @brief Default function to handle action replies
*/
ReturnValue_t handleActionReply();
ReturnValue_t handleActionReply(const uint8_t* rawFrame);
/**
* @brief Handles reply to upload centroid command
@ -427,16 +449,17 @@ class StarTrackerHandler : public DeviceHandlerBase {
/**
* @brief Handles reply to checksum command
*/
ReturnValue_t handleChecksumReply();
ReturnValue_t handleChecksumReply(const uint8_t* rawFrame);
/**
* @brief Handles all set parameter replies
*/
ReturnValue_t handleSetParamReply();
ReturnValue_t handleSetParamReply(const uint8_t* rawFrame);
ReturnValue_t handlePingReply();
ReturnValue_t handlePingReply(const uint8_t* rawFrame);
ReturnValue_t handleParamRequest(LocalPoolDataSetBase& dataset, size_t size);
ReturnValue_t handleParamRequest(const uint8_t* rawFrame, LocalPoolDataSetBase& dataset,
size_t size);
/**
* @brief Checks the loaded program by means of the version set
@ -446,7 +469,7 @@ class StarTrackerHandler : public DeviceHandlerBase {
/**
* @brief Handles the startup state machine
*/
void handleStartup(const uint8_t* parameterId);
void handleStartup(uint8_t parameterId);
/**
* @brief Handles telemtry replies and fills the appropriate dataset
@ -456,7 +479,7 @@ class StarTrackerHandler : public DeviceHandlerBase {
*
* @return returnvalue::OK if successful, otherwise error return value
*/
ReturnValue_t handleTm(LocalPoolDataSetBase& dataset, size_t size);
ReturnValue_t handleTm(const uint8_t* rawFrame, LocalPoolDataSetBase& dataset, size_t size);
/**
* @brief Checks if star tracker is in valid mode for executing the received command.

View File

@ -1,6 +1,9 @@
#include "StrHelper.h"
#include <fcntl.h>
#include <fsfw/filesystem/HasFileSystemIF.h>
#include <fsfw/tasks/TaskFactory.h>
#include <fsfw/timemanager/Stopwatch.h>
#include <linux/devices/startracker/StrComHandler.h>
#include <unistd.h>
#include <filesystem>
#include <fstream>
@ -8,16 +11,22 @@
#include "OBSWConfig.h"
#include "eive/definitions.h"
#include "fsfw/timemanager/Countdown.h"
#include "helpers.h"
#include "linux/devices/devicedefinitions/StarTrackerDefinitions.h"
#include "mission/utility/Filenaming.h"
#include "mission/utility/ProgressPrinter.h"
#include "mission/utility/Timestamp.h"
StrHelper::StrHelper(object_id_t objectId) : SystemObject(objectId) {}
using namespace returnvalue;
StrHelper::~StrHelper() {}
StrComHandler::StrComHandler(object_id_t objectId) : SystemObject(objectId) {
lock = MutexFactory::instance()->createMutex();
semaphore.acquire();
}
ReturnValue_t StrHelper::initialize() {
StrComHandler::~StrComHandler() {}
ReturnValue_t StrComHandler::initialize() {
#ifdef XIPHOS_Q7S
sdcMan = SdCardManager::instance();
if (sdcMan == nullptr) {
@ -28,53 +37,63 @@ ReturnValue_t StrHelper::initialize() {
return returnvalue::OK;
}
ReturnValue_t StrHelper::performOperation(uint8_t operationCode) {
ReturnValue_t StrComHandler::performOperation(uint8_t operationCode) {
ReturnValue_t result = returnvalue::OK;
semaphore.acquire();
while (true) {
switch (internalState) {
case InternalState::IDLE: {
semaphore.acquire();
lock->lockMutex();
state = InternalState::SLEEPING;
datalinkLayer.reset();
lock->unlockMutex();
semaphore.acquire();
switch (state) {
case InternalState::POLL_ONE_REPLY: {
// Stopwatch watch;
replyTimeout.setTimeout(200);
replyResult = readOneReply(static_cast<uint32_t>(state));
{
MutexGuard mg(lock);
replyWasReceived = true;
}
break;
}
case InternalState::UPLOAD_IMAGE: {
replyTimeout.setTimeout(200);
result = performImageUpload();
if (result == returnvalue::OK) {
triggerEvent(IMAGE_UPLOAD_SUCCESSFUL);
} else {
triggerEvent(IMAGE_UPLOAD_FAILED);
}
internalState = InternalState::IDLE;
break;
}
case InternalState::DOWNLOAD_IMAGE: {
replyTimeout.setTimeout(200);
result = performImageDownload();
if (result == returnvalue::OK) {
triggerEvent(IMAGE_DOWNLOAD_SUCCESSFUL);
} else {
triggerEvent(IMAGE_DOWNLOAD_FAILED);
}
internalState = InternalState::IDLE;
break;
}
case InternalState::FLASH_READ: {
replyTimeout.setTimeout(200);
result = performFlashRead();
if (result == returnvalue::OK) {
triggerEvent(FLASH_READ_SUCCESSFUL);
} else {
triggerEvent(FLASH_READ_FAILED);
}
internalState = InternalState::IDLE;
break;
}
case InternalState::FIRMWARE_UPDATE: {
replyTimeout.setTimeout(200);
result = performFirmwareUpdate();
if (result == returnvalue::OK) {
triggerEvent(FIRMWARE_UPDATE_SUCCESSFUL);
} else {
triggerEvent(FIRMWARE_UPDATE_FAILED);
}
internalState = InternalState::IDLE;
break;
}
default:
@ -84,18 +103,13 @@ ReturnValue_t StrHelper::performOperation(uint8_t operationCode) {
}
}
ReturnValue_t StrHelper::setComIF(DeviceCommunicationIF* communicationInterface_) {
uartComIF = dynamic_cast<SerialComIF*>(communicationInterface_);
if (uartComIF == nullptr) {
sif::warning << "StrHelper::initialize: Invalid uart com if" << std::endl;
return returnvalue::FAILED;
ReturnValue_t StrComHandler::startImageUpload(std::string fullname) {
{
MutexGuard mg(lock);
if (state != InternalState::SLEEPING) {
return BUSY;
}
}
return returnvalue::OK;
}
void StrHelper::setComCookie(CookieIF* comCookie_) { comCookie = comCookie_; }
ReturnValue_t StrHelper::startImageUpload(std::string fullname) {
#ifdef XIPHOS_Q7S
ReturnValue_t result = checkPath(fullname);
if (result != returnvalue::OK) {
@ -106,13 +120,22 @@ ReturnValue_t StrHelper::startImageUpload(std::string fullname) {
if (not std::filesystem::exists(fullname)) {
return FILE_NOT_EXISTS;
}
internalState = InternalState::UPLOAD_IMAGE;
{
MutexGuard mg(lock);
state = InternalState::UPLOAD_IMAGE;
}
semaphore.release();
terminate = false;
return returnvalue::OK;
}
ReturnValue_t StrHelper::startImageDownload(std::string path) {
ReturnValue_t StrComHandler::startImageDownload(std::string path) {
{
MutexGuard mg(lock);
if (state != InternalState::SLEEPING) {
return BUSY;
}
}
#ifdef XIPHOS_Q7S
ReturnValue_t result = checkPath(path);
if (result != returnvalue::OK) {
@ -123,19 +146,30 @@ ReturnValue_t StrHelper::startImageDownload(std::string path) {
return PATH_NOT_EXISTS;
}
downloadImage.path = path;
internalState = InternalState::DOWNLOAD_IMAGE;
{
MutexGuard mg(lock);
state = InternalState::DOWNLOAD_IMAGE;
}
terminate = false;
semaphore.release();
return returnvalue::OK;
}
void StrHelper::stopProcess() { terminate = true; }
void StrComHandler::stopProcess() { terminate = true; }
void StrHelper::setDownloadImageName(std::string filename) { downloadImage.filename = filename; }
void StrComHandler::setDownloadImageName(std::string filename) {
downloadImage.filename = filename;
}
void StrHelper::setFlashReadFilename(std::string filename) { flashRead.filename = filename; }
void StrComHandler::setFlashReadFilename(std::string filename) { flashRead.filename = filename; }
ReturnValue_t StrHelper::startFirmwareUpdate(std::string fullname) {
ReturnValue_t StrComHandler::startFirmwareUpdate(std::string fullname) {
{
MutexGuard mg(lock);
if (state != InternalState::SLEEPING) {
return BUSY;
}
}
#ifdef XIPHOS_Q7S
ReturnValue_t result = checkPath(fullname);
if (result != returnvalue::OK) {
@ -148,13 +182,23 @@ ReturnValue_t StrHelper::startFirmwareUpdate(std::string fullname) {
}
flashWrite.firstRegion = static_cast<uint8_t>(startracker::FirmwareRegions::FIRST);
flashWrite.lastRegion = static_cast<uint8_t>(startracker::FirmwareRegions::LAST);
internalState = InternalState::FIRMWARE_UPDATE;
{
MutexGuard mg(lock);
state = InternalState::FIRMWARE_UPDATE;
}
semaphore.release();
terminate = false;
return returnvalue::OK;
}
ReturnValue_t StrHelper::startFlashRead(std::string path, uint8_t startRegion, uint32_t length) {
ReturnValue_t StrComHandler::startFlashRead(std::string path, uint8_t startRegion,
uint32_t length) {
{
MutexGuard mg(lock);
if (state != InternalState::SLEEPING) {
return BUSY;
}
}
#ifdef XIPHOS_Q7S
ReturnValue_t result = checkPath(path);
if (result != returnvalue::OK) {
@ -167,17 +211,20 @@ ReturnValue_t StrHelper::startFlashRead(std::string path, uint8_t startRegion, u
}
flashRead.startRegion = startRegion;
flashRead.size = length;
internalState = InternalState::FLASH_READ;
{
MutexGuard mg(lock);
state = InternalState::FLASH_READ;
}
semaphore.release();
terminate = false;
return returnvalue::OK;
}
void StrHelper::disableTimestamping() { timestamping = false; }
void StrComHandler::disableTimestamping() { timestamping = false; }
void StrHelper::enableTimestamping() { timestamping = true; }
void StrComHandler::enableTimestamping() { timestamping = true; }
ReturnValue_t StrHelper::performImageDownload() {
ReturnValue_t StrComHandler::performImageDownload() {
#ifdef XIPHOS_Q7S
if (not sdcMan->getActiveSdCard()) {
return HasFileSystemIF::FILESYSTEM_INACTIVE;
@ -190,6 +237,7 @@ ReturnValue_t StrHelper::performImageDownload() {
struct DownloadActionRequest downloadReq;
uint32_t size = 0;
uint32_t retries = 0;
size_t replySize = 0;
std::string image = Filenaming::generateAbsoluteFilename(downloadImage.path,
downloadImage.filename, timestamping);
std::ofstream file(image, std::ios_base::out);
@ -202,21 +250,21 @@ ReturnValue_t StrHelper::performImageDownload() {
file.close();
return returnvalue::OK;
}
arc_pack_download_action_req(&downloadReq, commandBuffer, &size);
arc_pack_download_action_req(&downloadReq, cmdBuf.data(), &size);
result = sendAndRead(size, downloadReq.position);
if (result != returnvalue::OK) {
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
uartComIF->flushUartRxBuffer(comCookie);
serial::flushRxBuf(serialPort);
retries++;
continue;
}
file.close();
return result;
}
result = checkActionReply();
result = checkActionReply(replySize);
if (result != returnvalue::OK) {
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
uartComIF->flushUartRxBuffer(comCookie);
serial::flushRxBuf(serialPort);
retries++;
continue;
}
@ -226,15 +274,14 @@ ReturnValue_t StrHelper::performImageDownload() {
result = checkReplyPosition(downloadReq.position);
if (result != returnvalue::OK) {
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
uartComIF->flushUartRxBuffer(comCookie);
serial::flushRxBuf(serialPort);
retries++;
continue;
}
file.close();
return result;
}
file.write(reinterpret_cast<const char*>(datalinkLayer.getReply() + IMAGE_DATA_OFFSET),
CHUNK_SIZE);
file.write(reinterpret_cast<const char*>(replyPtr + IMAGE_DATA_OFFSET), CHUNK_SIZE);
#if OBSW_DEBUG_STARTRACKER == 1
progressPrinter.print(downloadReq.position);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
@ -245,7 +292,7 @@ ReturnValue_t StrHelper::performImageDownload() {
return returnvalue::OK;
}
ReturnValue_t StrHelper::performImageUpload() {
ReturnValue_t StrComHandler::performImageUpload() {
ReturnValue_t result = returnvalue::OK;
uint32_t size = 0;
uint32_t imageSize = 0;
@ -258,11 +305,14 @@ ReturnValue_t StrHelper::performImageUpload() {
#endif
std::memset(&uploadReq.data, 0, sizeof(uploadReq.data));
if (not std::filesystem::exists(uploadImage.uploadFile)) {
triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast<uint32_t>(internalState));
internalState = InternalState::IDLE;
triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast<uint32_t>(state));
return returnvalue::FAILED;
}
std::ifstream file(uploadImage.uploadFile, std::ifstream::binary);
if (file.bad()) {
return HasFileSystemIF::GENERIC_FILE_ERROR;
}
// Set position of next character to end of file input stream
file.seekg(0, file.end);
// tellg returns position of character in input stream
@ -272,26 +322,29 @@ ReturnValue_t StrHelper::performImageUpload() {
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
while ((uploadReq.position + 1) * SIZE_IMAGE_PART < imageSize) {
if (terminate) {
file.close();
return returnvalue::OK;
}
file.seekg(uploadReq.position * SIZE_IMAGE_PART, file.beg);
file.read(reinterpret_cast<char*>(uploadReq.data), SIZE_IMAGE_PART);
arc_pack_upload_action_req(&uploadReq, commandBuffer, &size);
arc_pack_upload_action_req(&uploadReq, cmdBuf.data(), &size);
result = sendAndRead(size, uploadReq.position);
if (result != returnvalue::OK) {
file.close();
return returnvalue::FAILED;
}
result = checkActionReply();
result = checkActionReply(replyLen);
if (result != returnvalue::OK) {
file.close();
return result;
}
#if OBSW_DEBUG_STARTRACKER == 1
progressPrinter.print((uploadReq.position + 1) * SIZE_IMAGE_PART);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
uploadReq.position++;
// This does a bit of delaying roughly every second
if (uploadReq.position % 50 == 0) {
// Some grace time for other tasks
TaskFactory::delayTask(2);
}
}
std::memset(uploadReq.data, 0, sizeof(uploadReq.data));
uint32_t remainder = imageSize - uploadReq.position * SIZE_IMAGE_PART;
@ -299,12 +352,12 @@ ReturnValue_t StrHelper::performImageUpload() {
file.read(reinterpret_cast<char*>(uploadReq.data), remainder);
file.close();
uploadReq.position++;
arc_pack_upload_action_req(&uploadReq, commandBuffer, &size);
arc_pack_upload_action_req(&uploadReq, cmdBuf.data(), &size);
result = sendAndRead(size, uploadReq.position);
if (result != returnvalue::OK) {
return returnvalue::FAILED;
}
result = checkActionReply();
result = checkActionReply(replyLen);
if (result != returnvalue::OK) {
return result;
}
@ -314,7 +367,7 @@ ReturnValue_t StrHelper::performImageUpload() {
return returnvalue::OK;
}
ReturnValue_t StrHelper::performFirmwareUpdate() {
ReturnValue_t StrComHandler::performFirmwareUpdate() {
using namespace startracker;
ReturnValue_t result = returnvalue::OK;
result = unlockAndEraseRegions(static_cast<uint32_t>(startracker::FirmwareRegions::FIRST),
@ -326,7 +379,7 @@ ReturnValue_t StrHelper::performFirmwareUpdate() {
return result;
}
ReturnValue_t StrHelper::performFlashWrite() {
ReturnValue_t StrComHandler::performFlashWrite() {
#ifdef XIPHOS_Q7S
if (not sdcMan->getActiveSdCard()) {
return HasFileSystemIF::FILESYSTEM_INACTIVE;
@ -336,13 +389,16 @@ ReturnValue_t StrHelper::performFlashWrite() {
uint32_t size = 0;
uint32_t bytesWritten = 0;
uint32_t fileSize = 0;
struct WriteActionRequest req;
if (not std::filesystem::exists(flashWrite.fullname)) {
triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast<uint32_t>(internalState));
internalState = InternalState::IDLE;
triggerEvent(STR_HELPER_FILE_NOT_EXISTS, static_cast<uint32_t>(state));
return returnvalue::FAILED;
}
std::ifstream file(flashWrite.fullname, std::ifstream::binary);
if (file.bad()) {
return returnvalue::FAILED;
}
file.seekg(0, file.end);
fileSize = file.tellg();
if (fileSize > FLASH_REGION_SIZE * (flashWrite.lastRegion - flashWrite.firstRegion)) {
@ -358,7 +414,6 @@ ReturnValue_t StrHelper::performFlashWrite() {
req.length = CHUNK_SIZE;
for (uint32_t idx = 0; idx < fileChunks; idx++) {
if (terminate) {
file.close();
return returnvalue::OK;
}
file.seekg(idx * CHUNK_SIZE, file.beg);
@ -368,21 +423,23 @@ ReturnValue_t StrHelper::performFlashWrite() {
bytesWritten = 0;
}
req.address = bytesWritten;
arc_pack_write_action_req(&req, commandBuffer, &size);
arc_pack_write_action_req(&req, cmdBuf.data(), &size);
result = sendAndRead(size, req.address);
if (result != returnvalue::OK) {
file.close();
return result;
}
result = checkActionReply();
result = checkActionReply(replyLen);
if (result != returnvalue::OK) {
file.close();
return result;
}
bytesWritten += CHUNK_SIZE;
#if OBSW_DEBUG_STARTRACKER == 1
progressPrinter.print(idx * CHUNK_SIZE);
#endif /* OBSW_DEBUG_STARTRACKER == 1 */
if (idx % 50 == 0) {
// Some grace time for other tasks
TaskFactory::delayTask(2);
}
}
uint32_t remainingBytes = fileSize - fileChunks * CHUNK_SIZE;
file.seekg((fileChunks - 1) * CHUNK_SIZE, file.beg);
@ -395,12 +452,12 @@ ReturnValue_t StrHelper::performFlashWrite() {
req.address = bytesWritten;
req.length = remainingBytes;
bytesWritten += remainingBytes;
arc_pack_write_action_req(&req, commandBuffer, &size);
arc_pack_write_action_req(&req, cmdBuf.data(), &size);
result = sendAndRead(size, req.address);
if (result != returnvalue::OK) {
return result;
}
result = checkActionReply();
result = checkActionReply(replyLen);
if (result != returnvalue::OK) {
return result;
}
@ -410,7 +467,7 @@ ReturnValue_t StrHelper::performFlashWrite() {
return returnvalue::OK;
}
ReturnValue_t StrHelper::performFlashRead() {
ReturnValue_t StrComHandler::performFlashRead() {
#ifdef XIPHOS_Q7S
if (not sdcMan->getActiveSdCard()) {
return HasFileSystemIF::FILESYSTEM_INACTIVE;
@ -442,29 +499,28 @@ ReturnValue_t StrHelper::performFlashRead() {
} else {
req.length = CHUNK_SIZE;
}
arc_pack_read_action_req(&req, commandBuffer, &size);
arc_pack_read_action_req(&req, cmdBuf.data(), &size);
result = sendAndRead(size, req.address);
if (result != returnvalue::OK) {
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
uartComIF->flushUartRxBuffer(comCookie);
serial::flushRxBuf(serialPort);
retries++;
continue;
}
file.close();
return result;
}
result = checkActionReply();
result = checkActionReply(replyLen);
if (result != returnvalue::OK) {
if (retries < CONFIG_MAX_DOWNLOAD_RETRIES) {
uartComIF->flushUartRxBuffer(comCookie);
serial::flushRxBuf(serialPort);
retries++;
continue;
}
file.close();
return result;
}
file.write(reinterpret_cast<const char*>(datalinkLayer.getReply() + FLASH_READ_DATA_OFFSET),
req.length);
file.write(reinterpret_cast<const char*>(replyPtr + FLASH_READ_DATA_OFFSET), req.length);
bytesRead += req.length;
req.address += req.length;
if (req.address >= FLASH_REGION_SIZE) {
@ -480,70 +536,29 @@ ReturnValue_t StrHelper::performFlashRead() {
return returnvalue::OK;
}
ReturnValue_t StrHelper::sendAndRead(size_t size, uint32_t parameter, uint32_t delayMs) {
ReturnValue_t StrComHandler::sendAndRead(size_t size, uint32_t failParameter) {
ReturnValue_t result = returnvalue::OK;
ReturnValue_t decResult = returnvalue::OK;
size_t receivedDataLen = 0;
uint8_t* receivedData = nullptr;
size_t bytesLeft = 0;
uint32_t missedReplies = 0;
datalinkLayer.encodeFrame(commandBuffer, size);
result = uartComIF->sendMessage(comCookie, datalinkLayer.getEncodedFrame(),
datalinkLayer.getEncodedLength());
if (result != returnvalue::OK) {
const uint8_t* sendData;
size_t txFrameLen = 0;
datalinkLayer.encodeFrame(cmdBuf.data(), size, &sendData, txFrameLen);
int writeResult = write(serialPort, sendData, txFrameLen);
if (writeResult < 0) {
sif::warning << "StrHelper::sendAndRead: Failed to send packet" << std::endl;
triggerEvent(STR_HELPER_SENDING_PACKET_FAILED, result, parameter);
triggerEvent(STR_HELPER_SENDING_PACKET_FAILED, result, failParameter);
return returnvalue::FAILED;
}
decResult = ArcsecDatalinkLayer::DEC_IN_PROGRESS;
while (decResult == ArcsecDatalinkLayer::DEC_IN_PROGRESS) {
Countdown delay(delayMs);
delay.resetTimer();
while (delay.isBusy()) {
}
result = uartComIF->requestReceiveMessage(comCookie, startracker::MAX_FRAME_SIZE * 2 + 2);
if (result != returnvalue::OK) {
sif::warning << "StrHelper::sendAndRead: Failed to request reply" << std::endl;
triggerEvent(STR_HELPER_REQUESTING_MSG_FAILED, result, parameter);
return returnvalue::FAILED;
}
result = uartComIF->readReceivedMessage(comCookie, &receivedData, &receivedDataLen);
if (result != returnvalue::OK) {
sif::warning << "StrHelper::sendAndRead: Failed to read received message" << std::endl;
triggerEvent(STR_HELPER_READING_REPLY_FAILED, result, parameter);
return returnvalue::FAILED;
}
if (receivedDataLen == 0 && missedReplies < MAX_POLLS) {
missedReplies++;
continue;
} else if ((receivedDataLen == 0) && (missedReplies >= MAX_POLLS)) {
triggerEvent(STR_HELPER_NO_REPLY, parameter);
return returnvalue::FAILED;
} else {
missedReplies = 0;
}
decResult = datalinkLayer.decodeFrame(receivedData, receivedDataLen, &bytesLeft);
if (bytesLeft != 0) {
// This should never happen
sif::warning << "StrHelper::sendAndRead: Bytes left after decoding" << std::endl;
triggerEvent(STR_HELPER_COM_ERROR, result, parameter);
return returnvalue::FAILED;
}
}
if (decResult != returnvalue::OK) {
triggerEvent(STR_HELPER_DEC_ERROR, decResult, parameter);
return returnvalue::FAILED;
}
return returnvalue::OK;
return readOneReply(failParameter);
}
ReturnValue_t StrHelper::checkActionReply() {
uint8_t type = datalinkLayer.getReplyFrameType();
ReturnValue_t StrComHandler::checkActionReply(size_t replySize) {
uint8_t type = str::getReplyFrameType(replyPtr);
if (type != TMTC_ACTIONREPLY) {
sif::warning << "StrHelper::checkActionReply: Received reply with invalid type ID" << std::endl;
return INVALID_TYPE_ID;
}
uint8_t status = datalinkLayer.getStatusField();
uint8_t status = str::getStatusField(replyPtr);
if (status != ArcsecDatalinkLayer::STATUS_OK) {
sif::warning << "StrHelper::checkActionReply: Status failure: "
<< static_cast<unsigned int>(status) << std::endl;
@ -552,9 +567,9 @@ ReturnValue_t StrHelper::checkActionReply() {
return returnvalue::OK;
}
ReturnValue_t StrHelper::checkReplyPosition(uint32_t expectedPosition) {
ReturnValue_t StrComHandler::checkReplyPosition(uint32_t expectedPosition) {
uint32_t receivedPosition = 0;
std::memcpy(&receivedPosition, datalinkLayer.getReply() + POS_OFFSET, sizeof(receivedPosition));
std::memcpy(&receivedPosition, replyPtr + POS_OFFSET, sizeof(receivedPosition));
if (receivedPosition != expectedPosition) {
triggerEvent(POSITION_MISMATCH, receivedPosition);
return returnvalue::FAILED;
@ -563,7 +578,7 @@ ReturnValue_t StrHelper::checkReplyPosition(uint32_t expectedPosition) {
}
#ifdef XIPHOS_Q7S
ReturnValue_t StrHelper::checkPath(std::string name) {
ReturnValue_t StrComHandler::checkPath(std::string name) {
if (name.substr(0, sizeof(config::SD_0_MOUNT_POINT)) == std::string(config::SD_0_MOUNT_POINT)) {
if (!sdcMan->isSdCardUsable(sd::SLOT_0)) {
sif::warning << "StrHelper::checkPath: SD card 0 not mounted" << std::endl;
@ -580,7 +595,112 @@ ReturnValue_t StrHelper::checkPath(std::string name) {
}
#endif
ReturnValue_t StrHelper::unlockAndEraseRegions(uint32_t from, uint32_t to) {
ReturnValue_t StrComHandler::initializeInterface(CookieIF* cookie) {
if (cookie == nullptr) {
return returnvalue::FAILED;
}
SerialCookie* serCookie = dynamic_cast<SerialCookie*>(cookie);
if (serCookie == nullptr) {
return DeviceCommunicationIF::INVALID_COOKIE_TYPE;
}
// comCookie = serCookie;
std::string devname = serCookie->getDeviceFile();
/* Get file descriptor */
serialPort = open(devname.c_str(), O_RDWR);
if (serialPort < 0) {
sif::warning << "StrComHandler: open call failed with error [" << errno << ", "
<< strerror(errno) << std::endl;
return returnvalue::FAILED;
}
// Setting up UART parameters
tty.c_cflag &= ~PARENB; // Clear parity bit
serial::setStopbits(tty, serCookie->getStopBits());
serial::setBitsPerWord(tty, BitsPerWord::BITS_8);
tty.c_cflag &= ~CRTSCTS; // Disable RTS/CTS hardware flow control
serial::enableRead(tty);
serial::ignoreCtrlLines(tty);
// Use non-canonical mode and clear echo flag
tty.c_lflag &= ~(ICANON | ECHO);
// Non-blocking mode, use polling
tty.c_cc[VTIME] = 0;
tty.c_cc[VMIN] = 0;
serial::setBaudrate(tty, serCookie->getBaudrate());
if (tcsetattr(serialPort, TCSANOW, &tty) != 0) {
sif::warning << "ScexUartReader::initializeInterface: tcsetattr call failed with error ["
<< errno << ", " << strerror(errno) << std::endl;
}
// Flush received and unread data
tcflush(serialPort, TCIOFLUSH);
return returnvalue::OK;
}
ReturnValue_t StrComHandler::sendMessage(CookieIF* cookie, const uint8_t* sendData,
size_t sendLen) {
{
MutexGuard mg(lock);
if (state != InternalState::SLEEPING) {
return BUSY;
}
}
serial::flushRxBuf(serialPort);
const uint8_t* txFrame;
size_t frameLen;
datalinkLayer.encodeFrame(sendData, sendLen, &txFrame, frameLen);
ssize_t bytesWritten = write(serialPort, txFrame, frameLen);
if (bytesWritten != static_cast<ssize_t>(frameLen)) {
sif::warning << "StrComHandler: Sending packet failed" << std::endl;
return returnvalue::FAILED;
}
// Hacky, but the alternatives look bleak. The raw data contains the information we need
// and there are not too many special cases.
if (sendData[0] == TMTC_ACTIONREQ) {
// 1 is a firmware boot request and 7 is a reboot request. For both, no reply is expected.
if (sendData[1] == 7 or sendData[1] == 1) {
return returnvalue::OK;
}
}
{
MutexGuard mg(lock);
state = InternalState::POLL_ONE_REPLY;
}
// Unlock task to perform reply reading.
semaphore.release();
return returnvalue::OK;
}
ReturnValue_t StrComHandler::getSendSuccess(CookieIF* cookie) { return returnvalue::OK; }
ReturnValue_t StrComHandler::requestReceiveMessage(CookieIF* cookie, size_t requestLen) {
return returnvalue::OK;
}
ReturnValue_t StrComHandler::readReceivedMessage(CookieIF* cookie, uint8_t** buffer, size_t* size) {
// Consider it a configuration error if the task is not done with a command -> reply cycle
// in time.
bool replyWasReceived = false;
{
MutexGuard mg(lock);
if (state != InternalState::SLEEPING) {
return BUSY;
}
replyWasReceived = this->replyWasReceived;
}
if (not replyWasReceived) {
*size = 0;
return returnvalue::OK;
}
if (replyResult == returnvalue::OK) {
*buffer = const_cast<uint8_t*>(replyPtr);
*size = replyLen;
}
return replyResult;
}
ReturnValue_t StrComHandler::unlockAndEraseRegions(uint32_t from, uint32_t to) {
ReturnValue_t result = returnvalue::OK;
#if OBSW_DEBUG_STARTRACKER == 1
ProgressPrinter progressPrinter("Unlock and erase", to - from);
@ -591,17 +711,20 @@ ReturnValue_t StrHelper::unlockAndEraseRegions(uint32_t from, uint32_t to) {
for (uint32_t idx = from; idx <= to; idx++) {
unlockReq.region = idx;
unlockReq.code = startracker::region_secrets::secret[idx];
arc_pack_unlock_action_req(&unlockReq, commandBuffer, &size);
sendAndRead(size, unlockReq.region);
result = checkActionReply();
arc_pack_unlock_action_req(&unlockReq, cmdBuf.data(), &size);
result = sendAndRead(size, unlockReq.region);
if (result != returnvalue::OK) {
return result;
}
result = checkActionReply(replyLen);
if (result != returnvalue::OK) {
sif::warning << "StrHelper::unlockAndEraseRegions: Failed to unlock region with id "
<< static_cast<unsigned int>(unlockReq.region) << std::endl;
return result;
}
eraseReq.region = idx;
arc_pack_erase_action_req(&eraseReq, commandBuffer, &size);
result = sendAndRead(size, eraseReq.region, FLASH_ERASE_DELAY);
arc_pack_erase_action_req(&eraseReq, cmdBuf.data(), &size);
result = sendAndRead(size, eraseReq.region);
if (result != returnvalue::OK) {
sif::warning << "StrHelper::unlockAndEraseRegions: Failed to erase region with id "
<< static_cast<unsigned int>(eraseReq.region) << std::endl;
@ -613,3 +736,48 @@ ReturnValue_t StrHelper::unlockAndEraseRegions(uint32_t from, uint32_t to) {
}
return result;
}
ReturnValue_t StrComHandler::handleSerialReception() {
ssize_t bytesRead = read(serialPort, reinterpret_cast<void*>(recBuf.data()),
static_cast<unsigned int>(recBuf.size()));
if (bytesRead == 0) {
return NO_SERIAL_DATA_READ;
} else if (bytesRead < 0) {
sif::warning << "StrComHandler: read call failed with error [" << errno << ", "
<< strerror(errno) << "]" << std::endl;
return FAILED;
} else if (bytesRead >= static_cast<int>(recBuf.size())) {
sif::error << "StrComHandler: Receive buffer too small for " << bytesRead << " bytes"
<< std::endl;
return FAILED;
} else if (bytesRead > 0) {
// sif::info << "Received " << bytesRead << " bytes from the STR" << std::endl;
// arrayprinter::print(recBuf.data(), bytesRead);
datalinkLayer.feedData(recBuf.data(), bytesRead);
}
return OK;
}
ReturnValue_t StrComHandler::readOneReply(uint32_t failParameter) {
ReturnValue_t result;
uint32_t nextDelayMs = 1;
replyTimeout.resetTimer();
while (true) {
handleSerialReception();
result = datalinkLayer.checkRingBufForFrame(&replyPtr, replyLen);
if (result == returnvalue::OK) {
return returnvalue::OK;
} else if (result != ArcsecDatalinkLayer::DEC_IN_PROGRESS) {
triggerEvent(STR_HELPER_DEC_ERROR, result, failParameter);
return DECODING_ERROR;
}
if (replyTimeout.hasTimedOut()) {
triggerEvent(STR_COM_REPLY_TIMEOUT, failParameter, replyTimeout.getTimeoutMs());
return RECEPTION_TIMEOUT;
}
TaskFactory::delayTask(nextDelayMs);
if (nextDelayMs < 32) {
nextDelayMs *= 2;
}
}
}

View File

@ -10,6 +10,8 @@
#include "bsp_q7s/fs/SdCardManager.h"
#endif
#include "arcsec/client/generated/actionreq.h"
#include "arcsec/common/generated/tmtcstructs.h"
#include "fsfw/devicehandlers/CookieIF.h"
#include "fsfw/objectmanager/SystemObject.h"
#include "fsfw/osal/linux/BinarySemaphore.h"
@ -17,18 +19,36 @@
#include "fsfw/tasks/ExecutableObjectIF.h"
#include "fsfw_hal/linux/serial/SerialComIF.h"
extern "C" {
#include "thirdparty/arcsec_star_tracker/client/generated/actionreq.h"
#include "thirdparty/arcsec_star_tracker/common/generated/tmtcstructs.h"
}
/**
* @brief Helper class for the star tracker handler to accelerate large data transfers.
*
* @author J. Meier
*/
class StrHelper : public SystemObject, public ExecutableObjectIF {
class StrComHandler : public SystemObject, public DeviceCommunicationIF, public ExecutableObjectIF {
public:
static const uint8_t INTERFACE_ID = CLASS_ID::STR_HELPER;
//! [EXPORT] : [COMMENT] SD card specified in path string not mounted
static const ReturnValue_t SD_NOT_MOUNTED = MAKE_RETURN_CODE(1);
//! [EXPORT] : [COMMENT] Specified file does not exist on filesystem
static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(2);
//! [EXPORT] : [COMMENT] Specified path does not exist
static const ReturnValue_t PATH_NOT_EXISTS = MAKE_RETURN_CODE(3);
//! [EXPORT] : [COMMENT] Failed to create download image or read flash file
static const ReturnValue_t FILE_CREATION_FAILED = MAKE_RETURN_CODE(4);
//! [EXPORT] : [COMMENT] Region in flash write/read reply does not match expected region
static const ReturnValue_t REGION_MISMATCH = MAKE_RETURN_CODE(5);
//! [EXPORT] : [COMMENT] Address in flash write/read reply does not match expected address
static const ReturnValue_t ADDRESS_MISMATCH = MAKE_RETURN_CODE(6);
//! [EXPORT] : [COMMENT] Length in flash write/read reply does not match expected length
static const ReturnValue_t LENGTH_MISMATCH = MAKE_RETURN_CODE(7);
//! [EXPORT] : [COMMENT] Status field in reply signals error
static const ReturnValue_t STATUS_ERROR = MAKE_RETURN_CODE(8);
//! [EXPORT] : [COMMENT] Reply has invalid type ID (should be of action reply type)
static const ReturnValue_t INVALID_TYPE_ID = MAKE_RETURN_CODE(9);
static const ReturnValue_t RECEPTION_TIMEOUT = MAKE_RETURN_CODE(10);
static const ReturnValue_t DECODING_ERROR = MAKE_RETURN_CODE(11);
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::STR_HELPER;
//! [EXPORT] : [COMMENT] Image upload failed
@ -57,39 +77,36 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
//! P1: Return code of failed communication interface read call
//! P1: Upload/download position for which the read call failed
static const Event STR_HELPER_COM_ERROR = MAKE_EVENT(10, severity::LOW);
//! [EXPORT] : [COMMENT] Star tracker did not send replies (maybe device is powered off)
//! P1: Position of upload or download packet for which no reply was sent
static const Event STR_HELPER_NO_REPLY = MAKE_EVENT(11, severity::LOW);
//! [EXPORT] : [COMMENT] Star tracker did not send a valid reply for a certain timeout.
//! P1: Position of upload or download packet for which the packet wa sent. P2: Timeout
static const Event STR_COM_REPLY_TIMEOUT = MAKE_EVENT(11, severity::LOW);
//! [EXPORT] : [COMMENT] Error during decoding of received reply occurred
// P1: Return value of decoding function
// P2: Position of upload/download packet, or address of flash write/read request
static const Event STR_HELPER_DEC_ERROR = MAKE_EVENT(12, severity::LOW);
//! P1: Return value of decoding function
//! P2: Position of upload/download packet, or address of flash write/read request
static const Event STR_HELPER_DEC_ERROR = MAKE_EVENT(13, severity::LOW);
//! [EXPORT] : [COMMENT] Position mismatch
//! P1: The expected position and thus the position for which the image upload/download failed
static const Event POSITION_MISMATCH = MAKE_EVENT(13, severity::LOW);
static const Event POSITION_MISMATCH = MAKE_EVENT(14, severity::LOW);
//! [EXPORT] : [COMMENT] Specified file does not exist
//! P1: Internal state of str helper
static const Event STR_HELPER_FILE_NOT_EXISTS = MAKE_EVENT(14, severity::LOW);
static const Event STR_HELPER_FILE_NOT_EXISTS = MAKE_EVENT(15, severity::LOW);
//! [EXPORT] : [COMMENT] Sending packet to star tracker failed
//! P1: Return code of communication interface sendMessage function
//! P2: Position of upload/download packet, or address of flash write/read request for which
//! sending failed
static const Event STR_HELPER_SENDING_PACKET_FAILED = MAKE_EVENT(15, severity::LOW);
static const Event STR_HELPER_SENDING_PACKET_FAILED = MAKE_EVENT(16, severity::LOW);
//! [EXPORT] : [COMMENT] Communication interface requesting reply failed
//! P1: Return code of failed request
//! P1: Upload/download position, or address of flash write/read request for which transmission
//! failed
static const Event STR_HELPER_REQUESTING_MSG_FAILED = MAKE_EVENT(16, severity::LOW);
static const Event STR_HELPER_REQUESTING_MSG_FAILED = MAKE_EVENT(17, severity::LOW);
StrHelper(object_id_t objectId);
virtual ~StrHelper();
StrComHandler(object_id_t objectId);
virtual ~StrComHandler();
ReturnValue_t initialize() override;
ReturnValue_t performOperation(uint8_t operationCode = 0) override;
ReturnValue_t setComIF(DeviceCommunicationIF* communicationInterface_);
void setComCookie(CookieIF* comCookie_);
/**
* @brief Starts sequence to upload image to star tracker
*
@ -148,26 +165,8 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
void enableTimestamping();
private:
static const uint8_t INTERFACE_ID = CLASS_ID::STR_HELPER;
//! [EXPORT] : [COMMENT] SD card specified in path string not mounted
static const ReturnValue_t SD_NOT_MOUNTED = MAKE_RETURN_CODE(0xA0);
//! [EXPORT] : [COMMENT] Specified file does not exist on filesystem
static const ReturnValue_t FILE_NOT_EXISTS = MAKE_RETURN_CODE(0xA1);
//! [EXPORT] : [COMMENT] Specified path does not exist
static const ReturnValue_t PATH_NOT_EXISTS = MAKE_RETURN_CODE(0xA2);
//! [EXPORT] : [COMMENT] Failed to create download image or read flash file
static const ReturnValue_t FILE_CREATION_FAILED = MAKE_RETURN_CODE(0xA3);
//! [EXPORT] : [COMMENT] Region in flash write/read reply does not match expected region
static const ReturnValue_t REGION_MISMATCH = MAKE_RETURN_CODE(0xA4);
//! [EXPORT] : [COMMENT] Address in flash write/read reply does not match expected address
static const ReturnValue_t ADDRESS_MISMATCH = MAKE_RETURN_CODE(0xA5);
//! [EXPORT] : [COMMENT] Length in flash write/read reply does not match expected length
static const ReturnValue_t LENGTH_MISMATCH = MAKE_RETURN_CODE(0xA6);
//! [EXPORT] : [COMMENT] Status field in reply signals error
static const ReturnValue_t STATUS_ERROR = MAKE_RETURN_CODE(0xA7);
//! [EXPORT] : [COMMENT] Reply has invalid type ID (should be of action reply type)
static const ReturnValue_t INVALID_TYPE_ID = MAKE_RETURN_CODE(0xA8);
//! [EXPORT] : [SKIP]
static constexpr ReturnValue_t NO_SERIAL_DATA_READ = MAKE_RETURN_CODE(128);
// Size of one image part which can be sent per action request
static const size_t SIZE_IMAGE_PART = 1024;
@ -179,25 +178,34 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
static const uint32_t MAX_POLLS = 10000;
static const uint8_t ACTION_DATA_OFFSET = 2;
static const uint8_t POS_OFFSET = 2;
static const uint8_t IMAGE_DATA_OFFSET = 5;
static const uint8_t FLASH_READ_DATA_OFFSET = 8;
static const uint8_t REGION_OFFSET = 2;
static const uint8_t ADDRESS_OFFSET = 3;
static const uint8_t LENGTH_OFFSET = 7;
static const uint8_t ACTION_DATA_OFFSET = 3;
static const uint8_t POS_OFFSET = 3;
static const uint8_t IMAGE_DATA_OFFSET = 6;
static const uint8_t FLASH_READ_DATA_OFFSET = 9;
static const uint8_t REGION_OFFSET = 3;
static const uint8_t ADDRESS_OFFSET = 4;
static const size_t CHUNK_SIZE = 1024;
static const size_t CONFIG_MAX_DOWNLOAD_RETRIES = 3;
static const uint32_t FLASH_ERASE_DELAY = 500;
enum class InternalState { IDLE, UPLOAD_IMAGE, DOWNLOAD_IMAGE, FLASH_READ, FIRMWARE_UPDATE };
enum class InternalState {
SLEEPING,
POLL_ONE_REPLY,
UPLOAD_IMAGE,
DOWNLOAD_IMAGE,
FLASH_READ,
FIRMWARE_UPDATE
};
InternalState internalState = InternalState::IDLE;
InternalState state = InternalState::SLEEPING;
ArcsecDatalinkLayer datalinkLayer;
MutexIF *lock;
BinarySemaphore semaphore;
Countdown replyTimeout = Countdown(20);
struct UploadImage {
// Name including absolute path of image to upload
std::string uploadFile;
@ -238,10 +246,16 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
FlashRead flashRead;
#ifdef XIPHOS_Q7S
SdCardManager* sdcMan = nullptr;
SdCardManager *sdcMan = nullptr;
#endif
uint8_t commandBuffer[startracker::MAX_FRAME_SIZE];
std::array<uint8_t, startracker::MAX_FRAME_SIZE> cmdBuf{};
std::array<uint8_t, 4096> recBuf{};
bool replyWasReceived = false;
const uint8_t *replyPtr = nullptr;
size_t replyLen = 0;
ReturnValue_t replyResult = returnvalue::OK;
bool terminate = false;
@ -251,17 +265,20 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
bool timestamping = true;
#endif
/**
* UART communication object responsible for low level access of star tracker
* Must be set by star tracker handler
*/
SerialComIF* uartComIF = nullptr;
// Communication cookie. Must be set by the star tracker handler
CookieIF* comCookie = nullptr;
int serialPort = 0;
struct termios tty = {};
// Queue id of raw data receiver
MessageQueueId_t rawDataReceiver = MessageQueueIF::NO_QUEUE;
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 handleSerialReception();
/**
* @brief Performs image uploading
*/
@ -302,21 +319,23 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
/**
* @brief Sends packet to the star tracker and reads reply by using the communication
* interface
*
* @details
* The reply frame is stored in the data link layer helper. A pointer to the start of the frame
* is assigned to the @replyPtr member of this class. The frame length will be assigned to
* the @replyLen member.
* @param size Size of data beforehand written to the commandBuffer
* @param parameter Parameter 2 of trigger event function
* @param delayMs Delay in milliseconds between send and receive call
*
* @return returnvalue::OK if successful, otherwise returnvalue::FAILED
*/
ReturnValue_t sendAndRead(size_t size, uint32_t parameter, uint32_t delayMs = 0);
ReturnValue_t sendAndRead(size_t size, uint32_t parameter);
/**
* @brief Checks the header (type id and status fields) of the action reply
*
* @return returnvalue::OK if reply confirms success of packet transfer, otherwise REUTRN_FAILED
*/
ReturnValue_t checkActionReply();
ReturnValue_t checkActionReply(size_t replySize);
/**
* @brief Checks the position field in a star tracker upload/download reply.
@ -345,6 +364,15 @@ class StrHelper : public SystemObject, public ExecutableObjectIF {
*
*/
ReturnValue_t unlockAndEraseRegions(uint32_t from, uint32_t to);
/**
* The reply frame is stored in the data link layer helper. A pointer to the start of the frame
* is assigned to the @replyPtr member of this class. The frame length will be assigned to
* the @replyLen member.
* @param failParameter
* @return
*/
ReturnValue_t readOneReply(uint32_t failParameter);
};
#endif /* BSP_Q7S_DEVICES_STRHELPER_H_ */

View File

@ -0,0 +1,7 @@
#include "helpers.h"
uint8_t str::getReplyFrameType(const uint8_t* rawFrame) { return rawFrame[0]; }
uint8_t str::getId(const uint8_t* rawFrame) { return rawFrame[1]; }
uint8_t str::getStatusField(const uint8_t* rawFrame) { return rawFrame[2]; }

View File

@ -0,0 +1,17 @@
#ifndef LINUX_DEVICES_STARTRACKER_HELPERS_H_
#define LINUX_DEVICES_STARTRACKER_HELPERS_H_
#include "arcsec/common/genericstructs.h"
namespace str {
/**
* @brief Returns the frame type field of a decoded frame.
*/
uint8_t getReplyFrameType(const uint8_t* rawFrame);
uint8_t getId(const uint8_t* rawFrame);
uint8_t getStatusField(const uint8_t* rawFrame);
} // namespace str
#endif /* LINUX_DEVICES_STARTRACKER_HELPERS_H_ */

View File

@ -1,6 +1,6 @@
#include "StarTrackerJsonCommands.h"
#include "strJsonCommands.h"
#include "ArcsecJsonKeys.h"
#include "arcsecJsonKeys.h"
Limits::Limits() : ArcsecJsonParamBase(arcseckeys::LIMITS) {}

View File

@ -1,7 +1,7 @@
/**
* @brief Auto-generated event translation file. Contains 267 translations.
* @brief Auto-generated event translation file. Contains 279 translations.
* @details
* Generated on: 2023-03-01 18:34:32
* Generated on: 2023-03-24 17:28:23
*/
#include "translateEvents.h"
@ -35,11 +35,11 @@ const char *INVALID_DEVICE_COMMAND_STRING = "INVALID_DEVICE_COMMAND";
const char *MONITORING_LIMIT_EXCEEDED_STRING = "MONITORING_LIMIT_EXCEEDED";
const char *MONITORING_AMBIGUOUS_STRING = "MONITORING_AMBIGUOUS";
const char *DEVICE_WANTS_HARD_REBOOT_STRING = "DEVICE_WANTS_HARD_REBOOT";
const char *SWITCH_WENT_OFF_STRING = "SWITCH_WENT_OFF";
const char *FUSE_CURRENT_HIGH_STRING = "FUSE_CURRENT_HIGH";
const char *FUSE_WENT_OFF_STRING = "FUSE_WENT_OFF";
const char *POWER_ABOVE_HIGH_LIMIT_STRING = "POWER_ABOVE_HIGH_LIMIT";
const char *POWER_BELOW_LOW_LIMIT_STRING = "POWER_BELOW_LOW_LIMIT";
const char *SWITCH_WENT_OFF_STRING = "SWITCH_WENT_OFF";
const char *HEATER_ON_STRING = "HEATER_ON";
const char *HEATER_OFF_STRING = "HEATER_OFF";
const char *HEATER_TIMEOUT_STRING = "HEATER_TIMEOUT";
@ -96,7 +96,9 @@ const char *SAFE_RATE_VIOLATION_STRING = "SAFE_RATE_VIOLATION";
const char *SAFE_RATE_RECOVERY_STRING = "SAFE_RATE_RECOVERY";
const char *MULTIPLE_RW_INVALID_STRING = "MULTIPLE_RW_INVALID";
const char *MEKF_INVALID_INFO_STRING = "MEKF_INVALID_INFO";
const char *MEKF_RECOVERY_STRING = "MEKF_RECOVERY";
const char *MEKF_INVALID_MODE_VIOLATION_STRING = "MEKF_INVALID_MODE_VIOLATION";
const char *SAFE_MODE_CONTROLLER_FAILURE_STRING = "SAFE_MODE_CONTROLLER_FAILURE";
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";
@ -171,7 +173,7 @@ const char *FIRMWARE_UPDATE_SUCCESSFUL_STRING = "FIRMWARE_UPDATE_SUCCESSFUL";
const char *FIRMWARE_UPDATE_FAILED_STRING = "FIRMWARE_UPDATE_FAILED";
const char *STR_HELPER_READING_REPLY_FAILED_STRING = "STR_HELPER_READING_REPLY_FAILED";
const char *STR_HELPER_COM_ERROR_STRING = "STR_HELPER_COM_ERROR";
const char *STR_HELPER_NO_REPLY_STRING = "STR_HELPER_NO_REPLY";
const char *STR_COM_REPLY_TIMEOUT_STRING = "STR_COM_REPLY_TIMEOUT";
const char *STR_HELPER_DEC_ERROR_STRING = "STR_HELPER_DEC_ERROR";
const char *POSITION_MISMATCH_STRING = "POSITION_MISMATCH";
const char *STR_HELPER_FILE_NOT_EXISTS_STRING = "STR_HELPER_FILE_NOT_EXISTS";
@ -207,6 +209,10 @@ const char *TRANSITION_OTHER_SIDE_FAILED_STRING = "TRANSITION_OTHER_SIDE_FAILED"
const char *NOT_ENOUGH_DEVICES_DUAL_MODE_STRING = "NOT_ENOUGH_DEVICES_DUAL_MODE";
const char *POWER_STATE_MACHINE_TIMEOUT_STRING = "POWER_STATE_MACHINE_TIMEOUT";
const char *SIDE_SWITCH_TRANSITION_NOT_ALLOWED_STRING = "SIDE_SWITCH_TRANSITION_NOT_ALLOWED";
const char *TRANSITION_OTHER_SIDE_FAILED_12900_STRING = "TRANSITION_OTHER_SIDE_FAILED_12900";
const char *NOT_ENOUGH_DEVICES_DUAL_MODE_12901_STRING = "NOT_ENOUGH_DEVICES_DUAL_MODE_12901";
const char *POWER_STATE_MACHINE_TIMEOUT_12902_STRING = "POWER_STATE_MACHINE_TIMEOUT_12902";
const char *SIDE_SWITCH_TRANSITION_NOT_ALLOWED_12903_STRING = "SIDE_SWITCH_TRANSITION_NOT_ALLOWED_12903";
const char *CHILDREN_LOST_MODE_STRING = "CHILDREN_LOST_MODE";
const char *GPS_FIX_CHANGE_STRING = "GPS_FIX_CHANGE";
const char *CANT_GET_FIX_STRING = "CANT_GET_FIX";
@ -257,6 +263,9 @@ const char *REBOOT_HW_STRING = "REBOOT_HW";
const char *NO_SD_CARD_ACTIVE_STRING = "NO_SD_CARD_ACTIVE";
const char *VERSION_INFO_STRING = "VERSION_INFO";
const char *CURRENT_IMAGE_INFO_STRING = "CURRENT_IMAGE_INFO";
const char *REBOOT_COUNTER_STRING = "REBOOT_COUNTER";
const char *INDIVIDUAL_BOOT_COUNTS_STRING = "INDIVIDUAL_BOOT_COUNTS";
const char *I2C_UNAVAILABLE_REBOOT_STRING = "I2C_UNAVAILABLE_REBOOT";
const char *NO_VALID_SENSOR_TEMPERATURE_STRING = "NO_VALID_SENSOR_TEMPERATURE";
const char *NO_HEALTHY_HEATER_AVAILABLE_STRING = "NO_HEALTHY_HEATER_AVAILABLE";
const char *SYRLINKS_OVERHEATING_STRING = "SYRLINKS_OVERHEATING";
@ -267,6 +276,14 @@ const char *PLPCDU_OVERHEATING_STRING = "PLPCDU_OVERHEATING";
const char *TX_TIMER_EXPIRED_STRING = "TX_TIMER_EXPIRED";
const char *BIT_LOCK_TX_ON_STRING = "BIT_LOCK_TX_ON";
const char *POSSIBLE_FILE_CORRUPTION_STRING = "POSSIBLE_FILE_CORRUPTION";
const char *FILE_TOO_LARGE_STRING = "FILE_TOO_LARGE";
const char *BUSY_DUMPING_EVENT_STRING = "BUSY_DUMPING_EVENT";
const char *DUMP_WAS_CANCELLED_STRING = "DUMP_WAS_CANCELLED";
const char *DUMP_OK_STORE_DONE_STRING = "DUMP_OK_STORE_DONE";
const char *DUMP_NOK_STORE_DONE_STRING = "DUMP_NOK_STORE_DONE";
const char *DUMP_MISC_STORE_DONE_STRING = "DUMP_MISC_STORE_DONE";
const char *DUMP_HK_STORE_DONE_STRING = "DUMP_HK_STORE_DONE";
const char *DUMP_CFDP_STORE_DONE_STRING = "DUMP_CFDP_STORE_DONE";
const char *translateEvents(Event event) {
switch ((event & 0xFFFF)) {
@ -330,16 +347,16 @@ const char *translateEvents(Event event) {
return MONITORING_AMBIGUOUS_STRING;
case (2811):
return DEVICE_WANTS_HARD_REBOOT_STRING;
case (4201):
return FUSE_CURRENT_HIGH_STRING;
case (4202):
return FUSE_WENT_OFF_STRING;
case (4204):
return POWER_ABOVE_HIGH_LIMIT_STRING;
case (4205):
return POWER_BELOW_LOW_LIMIT_STRING;
case (4300):
return SWITCH_WENT_OFF_STRING;
case (4301):
return FUSE_CURRENT_HIGH_STRING;
case (4302):
return FUSE_WENT_OFF_STRING;
case (4304):
return POWER_ABOVE_HIGH_LIMIT_STRING;
case (4305):
return POWER_BELOW_LOW_LIMIT_STRING;
case (5000):
return HEATER_ON_STRING;
case (5001):
@ -453,7 +470,11 @@ const char *translateEvents(Event event) {
case (11203):
return MEKF_INVALID_INFO_STRING;
case (11204):
return MEKF_RECOVERY_STRING;
case (11205):
return MEKF_INVALID_MODE_VIOLATION_STRING;
case (11206):
return SAFE_MODE_CONTROLLER_FAILURE_STRING;
case (11300):
return SWITCH_CMD_SENT_STRING;
case (11301):
@ -603,16 +624,16 @@ const char *translateEvents(Event event) {
case (12510):
return STR_HELPER_COM_ERROR_STRING;
case (12511):
return STR_HELPER_NO_REPLY_STRING;
case (12512):
return STR_HELPER_DEC_ERROR_STRING;
return STR_COM_REPLY_TIMEOUT_STRING;
case (12513):
return POSITION_MISMATCH_STRING;
return STR_HELPER_DEC_ERROR_STRING;
case (12514):
return STR_HELPER_FILE_NOT_EXISTS_STRING;
return POSITION_MISMATCH_STRING;
case (12515):
return STR_HELPER_SENDING_PACKET_FAILED_STRING;
return STR_HELPER_FILE_NOT_EXISTS_STRING;
case (12516):
return STR_HELPER_SENDING_PACKET_FAILED_STRING;
case (12517):
return STR_HELPER_REQUESTING_MSG_FAILED_STRING;
case (12600):
return MPSOC_FLASH_WRITE_FAILED_STRING;
@ -674,6 +695,14 @@ const char *translateEvents(Event event) {
return POWER_STATE_MACHINE_TIMEOUT_STRING;
case (12803):
return SIDE_SWITCH_TRANSITION_NOT_ALLOWED_STRING;
case (12900):
return TRANSITION_OTHER_SIDE_FAILED_12900_STRING;
case (12901):
return NOT_ENOUGH_DEVICES_DUAL_MODE_12901_STRING;
case (12902):
return POWER_STATE_MACHINE_TIMEOUT_12902_STRING;
case (12903):
return SIDE_SWITCH_TRANSITION_NOT_ALLOWED_12903_STRING;
case (13000):
return CHILDREN_LOST_MODE_STRING;
case (13100):
@ -774,6 +803,12 @@ const char *translateEvents(Event event) {
return VERSION_INFO_STRING;
case (14006):
return CURRENT_IMAGE_INFO_STRING;
case (14007):
return REBOOT_COUNTER_STRING;
case (14008):
return INDIVIDUAL_BOOT_COUNTS_STRING;
case (14010):
return I2C_UNAVAILABLE_REBOOT_STRING;
case (14100):
return NO_VALID_SENSOR_TEMPERATURE_STRING;
case (14101):
@ -794,6 +829,22 @@ const char *translateEvents(Event event) {
return BIT_LOCK_TX_ON_STRING;
case (14300):
return POSSIBLE_FILE_CORRUPTION_STRING;
case (14301):
return FILE_TOO_LARGE_STRING;
case (14302):
return BUSY_DUMPING_EVENT_STRING;
case (14303):
return DUMP_WAS_CANCELLED_STRING;
case (14305):
return DUMP_OK_STORE_DONE_STRING;
case (14306):
return DUMP_NOK_STORE_DONE_STRING;
case (14307):
return DUMP_MISC_STORE_DONE_STRING;
case (14308):
return DUMP_HK_STORE_DONE_STRING;
case (14309):
return DUMP_CFDP_STORE_DONE_STRING;
default:
return "UNKNOWN_EVENT";
}

View File

@ -1,8 +1,8 @@
/**
* @brief Auto-generated object translation file.
* @details
* Contains 161 translations.
* Generated on: 2023-03-01 18:34:32
* Contains 173 translations.
* Generated on: 2023-03-24 17:28:23
*/
#include "translateObjects.h"
@ -49,10 +49,14 @@ const char *PLPCDU_HANDLER_STRING = "PLPCDU_HANDLER";
const char *RAD_SENSOR_STRING = "RAD_SENSOR";
const char *PLOC_UPDATER_STRING = "PLOC_UPDATER";
const char *PLOC_MEMORY_DUMPER_STRING = "PLOC_MEMORY_DUMPER";
const char *STR_HELPER_STRING = "STR_HELPER";
const char *STR_COM_IF_STRING = "STR_COM_IF";
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 *PTME_VC0_LIVE_TM_STRING = "PTME_VC0_LIVE_TM";
const char *PTME_VC1_LOG_TM_STRING = "PTME_VC1_LOG_TM";
const char *PTME_VC2_HK_TM_STRING = "PTME_VC2_HK_TM";
const char *PTME_VC3_CFDP_TM_STRING = "PTME_VC3_CFDP_TM";
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";
@ -81,6 +85,7 @@ const char *RTD_13_IC16_PLPCDU_HEATSPREADER_STRING = "RTD_13_IC16_PLPCDU_HEATSPR
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_HANDLER_STRING = "SYRLINKS_HANDLER";
const char *SYRLINKS_COM_HANDLER_STRING = "SYRLINKS_COM_HANDLER";
const char *ARDUINO_COM_IF_STRING = "ARDUINO_COM_IF";
const char *GPIO_IF_STRING = "GPIO_IF";
const char *SCEX_UART_READER_STRING = "SCEX_UART_READER";
@ -143,12 +148,15 @@ 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 *HEATER_7_SYRLINKS_STRING = "HEATER_7_SYRLINKS";
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 *RW_ASSY_STRING = "RW_ASSY";
const char *CAM_SWITCHER_STRING = "CAM_SWITCHER";
const char *SYRLINKS_ASSY_STRING = "SYRLINKS_ASSY";
const char *IMTQ_ASSY_STRING = "IMTQ_ASSY";
const char *STR_ASSY_STRING = "STR_ASSY";
const char *TM_FUNNEL_STRING = "TM_FUNNEL";
const char *PUS_TM_FUNNEL_STRING = "PUS_TM_FUNNEL";
const char *CFDP_TM_FUNNEL_STRING = "CFDP_TM_FUNNEL";
@ -164,7 +172,11 @@ const char *OK_TM_STORE_STRING = "OK_TM_STORE";
const char *NOT_OK_TM_STORE_STRING = "NOT_OK_TM_STORE";
const char *HK_TM_STORE_STRING = "HK_TM_STORE";
const char *CFDP_TM_STORE_STRING = "CFDP_TM_STORE";
const char *CCSDS_IP_CORE_BRIDGE_STRING = "CCSDS_IP_CORE_BRIDGE";
const char *LIVE_TM_TASK_STRING = "LIVE_TM_TASK";
const char *LOG_STORE_AND_TM_TASK_STRING = "LOG_STORE_AND_TM_TASK";
const char *HK_STORE_AND_TM_TASK_STRING = "HK_STORE_AND_TM_TASK";
const char *CFDP_STORE_AND_TM_TASK_STRING = "CFDP_STORE_AND_TM_TASK";
const char *DOWNLINK_RAM_STORE_STRING = "DOWNLINK_RAM_STORE";
const char *THERMAL_TEMP_INSERTER_STRING = "THERMAL_TEMP_INSERTER";
const char *NO_OBJECT_STRING = "NO_OBJECT";
@ -257,13 +269,21 @@ const char *translateObject(object_id_t object) {
case 0x44330001:
return PLOC_MEMORY_DUMPER_STRING;
case 0x44330002:
return STR_HELPER_STRING;
return STR_COM_IF_STRING;
case 0x44330003:
return PLOC_MPSOC_HELPER_STRING;
case 0x44330004:
return AXI_PTME_CONFIG_STRING;
case 0x44330005:
return PTME_CONFIG_STRING;
case 0x44330006:
return PTME_VC0_LIVE_TM_STRING;
case 0x44330007:
return PTME_VC1_LOG_TM_STRING;
case 0x44330008:
return PTME_VC2_HK_TM_STRING;
case 0x44330009:
return PTME_VC3_CFDP_TM_STRING;
case 0x44330015:
return PLOC_MPSOC_HANDLER_STRING;
case 0x44330016:
@ -320,6 +340,8 @@ const char *translateObject(object_id_t object) {
return RTD_15_IC18_IMTQ_STRING;
case 0x445300A3:
return SYRLINKS_HANDLER_STRING;
case 0x445300A4:
return SYRLINKS_COM_HANDLER_STRING;
case 0x49000000:
return ARDUINO_COM_IF_STRING;
case 0x49010005:
@ -445,7 +467,7 @@ const char *translateObject(object_id_t object) {
case 0x60000006:
return HEATER_6_DRO_STRING;
case 0x60000007:
return HEATER_7_HPA_STRING;
return HEATER_7_SYRLINKS_STRING;
case 0x73000001:
return ACS_BOARD_ASS_STRING;
case 0x73000002:
@ -453,9 +475,15 @@ const char *translateObject(object_id_t object) {
case 0x73000003:
return TCS_BOARD_ASS_STRING;
case 0x73000004:
return RW_ASS_STRING;
return RW_ASSY_STRING;
case 0x73000006:
return CAM_SWITCHER_STRING;
case 0x73000007:
return SYRLINKS_ASSY_STRING;
case 0x73000008:
return IMTQ_ASSY_STRING;
case 0x73000009:
return STR_ASSY_STRING;
case 0x73000100:
return TM_FUNNEL_STRING;
case 0x73000101:
@ -486,8 +514,16 @@ const char *translateObject(object_id_t object) {
return HK_TM_STORE_STRING;
case 0x73030000:
return CFDP_TM_STORE_STRING;
case 0x73500000:
return CCSDS_IP_CORE_BRIDGE_STRING;
case 0x73040000:
return LIVE_TM_TASK_STRING;
case 0x73040001:
return LOG_STORE_AND_TM_TASK_STRING;
case 0x73040002:
return HK_STORE_AND_TM_TASK_STRING;
case 0x73040003:
return CFDP_STORE_AND_TM_TASK_STRING;
case 0x73040004:
return DOWNLINK_RAM_STORE_STRING;
case 0x90000003:
return THERMAL_TEMP_INSERTER_STRING;
case 0xFFFFFFFF:

View File

@ -71,6 +71,22 @@ ReturnValue_t AxiPtmeConfig::disableTxclockInversion() {
return returnvalue::OK;
}
ReturnValue_t AxiPtmeConfig::enableBatPriorityBit() {
ReturnValue_t result = writeBit(COMMON_CONFIG_REG, true, BitPos::EN_BAT_PRIORITY);
if (result != returnvalue::OK) {
return result;
}
return returnvalue::OK;
}
ReturnValue_t AxiPtmeConfig::disableBatPriorityBit() {
ReturnValue_t result = writeBit(COMMON_CONFIG_REG, false, BitPos::EN_BAT_PRIORITY);
if (result != returnvalue::OK) {
return result;
}
return returnvalue::OK;
}
ReturnValue_t AxiPtmeConfig::writeReg(uint32_t regOffset, uint32_t writeVal) {
ReturnValue_t result = returnvalue::OK;
result = mutex->lockMutex(timeoutType, mutexTimeout);

View File

@ -54,6 +54,9 @@ class AxiPtmeConfig : public SystemObject {
ReturnValue_t enableTxclockInversion();
ReturnValue_t disableTxclockInversion();
ReturnValue_t enableBatPriorityBit();
ReturnValue_t disableBatPriorityBit();
private:
// Address of register storing the bitrate configuration parameter
static const uint32_t CADU_BITRATE_REG = 0x0;
@ -61,7 +64,7 @@ class AxiPtmeConfig : public SystemObject {
static const uint32_t COMMON_CONFIG_REG = 0x4;
static const uint32_t ADRESS_DIVIDER = 4;
enum class BitPos : uint32_t { EN_TX_CLK_MANIPULATOR, INVERT_CLOCK };
enum class BitPos : uint32_t { EN_TX_CLK_MANIPULATOR = 0, INVERT_CLOCK = 1, EN_BAT_PRIORITY = 2 };
std::string axiUio;
std::string uioMap;

View File

@ -1,5 +1,6 @@
#include <fsfw_hal/linux/uio/UioMapper.h>
#include <linux/ipcore/PapbVcInterface.h>
#include <unistd.h>
#include "fsfw/serviceinterface/ServiceInterface.h"
@ -15,48 +16,67 @@ PapbVcInterface::~PapbVcInterface() {}
ReturnValue_t PapbVcInterface::initialize() {
UioMapper uioMapper(uioFile, mapNum);
return uioMapper.getMappedAdress(&vcBaseReg, UioMapper::Permissions::WRITE_ONLY);
uint32_t* baseReg;
ReturnValue_t result = uioMapper.getMappedAdress(&baseReg, UioMapper::Permissions::WRITE_ONLY);
if (result != returnvalue::OK) {
return result;
}
vcBaseReg = baseReg;
return returnvalue::OK;
}
ReturnValue_t PapbVcInterface::write(const uint8_t* data, size_t size) {
if (pollPapbBusySignal() == returnvalue::OK) {
if (pollPapbBusySignal(0, 0) == returnvalue::OK) {
startPacketTransfer();
} else {
return DirectTmSinkIF::IS_BUSY;
}
for (size_t idx = 0; idx < size; idx++) {
if (pollPapbBusySignal() == returnvalue::OK) {
*(vcBaseReg + DATA_REG_OFFSET) = static_cast<uint32_t>(*(data + idx));
if (pollPapbBusySignal(10, 10) == returnvalue::OK) {
*(vcBaseReg + DATA_REG_OFFSET) = static_cast<uint32_t>(data[idx]);
} else {
sif::warning << "PapbVcInterface::write: Only written " << idx << " of " << size << " data"
<< std::endl;
abortPacketTransfer();
return returnvalue::FAILED;
}
}
if (pollPapbBusySignal() == returnvalue::OK) {
endPacketTransfer();
if (pollPapbBusySignal(10, 10) == returnvalue::OK) {
completePacketTransfer();
} else {
abortPacketTransfer();
return returnvalue::FAILED;
}
return returnvalue::OK;
}
void PapbVcInterface::startPacketTransfer() { *vcBaseReg = CONFIG_START; }
void PapbVcInterface::endPacketTransfer() { *vcBaseReg = CONFIG_END; }
void PapbVcInterface::completePacketTransfer() { *vcBaseReg = CONFIG_END; }
ReturnValue_t PapbVcInterface::pollPapbBusySignal() {
ReturnValue_t PapbVcInterface::pollPapbBusySignal(uint32_t maxPollRetries,
uint32_t retryDelayUs) const {
gpio::Levels papbBusyState = gpio::Levels::LOW;
ReturnValue_t result = returnvalue::OK;
ReturnValue_t result;
uint32_t busyIdx = 0;
/** Check if PAPB interface is ready to receive data */
result = gpioComIF->readGpio(papbBusyId, papbBusyState);
if (result != returnvalue::OK) {
sif::warning << "PapbVcInterface::pollPapbBusySignal: Failed to read papb busy signal"
<< std::endl;
return returnvalue::FAILED;
}
if (papbBusyState == gpio::Levels::LOW) {
sif::warning << "PapbVcInterface::pollPapbBusySignal: PAPB busy" << std::endl;
return PAPB_BUSY;
}
while (true) {
/** Check if PAPB interface is ready to receive data */
result = gpioComIF->readGpio(papbBusyId, papbBusyState);
if (result != returnvalue::OK) {
sif::warning << "PapbVcInterface::pollPapbBusySignal: Failed to read papb busy signal"
<< std::endl;
return returnvalue::FAILED;
}
if (papbBusyState == gpio::Levels::HIGH) {
return returnvalue::OK;
}
busyIdx++;
if (busyIdx >= maxPollRetries) {
return PAPB_BUSY;
}
usleep(retryDelayUs);
}
return returnvalue::OK;
}
@ -80,6 +100,10 @@ void PapbVcInterface::isVcInterfaceBufferEmpty() {
return;
}
bool PapbVcInterface::isBusy() const { return pollPapbBusySignal(0, 0) == PAPB_BUSY; }
void PapbVcInterface::cancelTransfer() { abortPacketTransfer(); }
ReturnValue_t PapbVcInterface::sendTestFrame() {
/** Size of one complete transfer frame data field amounts to 1105 bytes */
uint8_t testPacket[1105];
@ -96,3 +120,5 @@ ReturnValue_t PapbVcInterface::sendTestFrame() {
return returnvalue::OK;
}
void PapbVcInterface::abortPacketTransfer() { *vcBaseReg = CONFIG_ABORT; }

View File

@ -3,10 +3,10 @@
#include <fsfw_hal/common/gpio/gpioDefinitions.h>
#include <fsfw_hal/linux/gpio/LinuxLibgpioIF.h>
#include <linux/ipcore/VirtualChannelIF.h>
#include "OBSWConfig.h"
#include "fsfw/returnvalues/returnvalue.h"
#include "linux/ipcore/VcInterfaceIF.h"
/**
* @brief This class handles the transmission of data to a virtual channel of the PTME IP Core
@ -14,7 +14,7 @@
*
* @author J. Meier
*/
class PapbVcInterface : public VcInterfaceIF {
class PapbVcInterface : public VirtualChannelIF {
public:
/**
* @brief Constructor
@ -32,8 +32,17 @@ class PapbVcInterface : public VcInterfaceIF {
std::string uioFile, int mapNum);
virtual ~PapbVcInterface();
bool isBusy() const override;
/**
*
* @param data
* @param size
* @return returnvalue::OK on successfull write, PAPB_BUSY if PAPB is busy.
*/
ReturnValue_t write(const uint8_t* data, size_t size) override;
void cancelTransfer() override;
ReturnValue_t initialize() override;
private:
@ -44,16 +53,21 @@ class PapbVcInterface : public VcInterfaceIF {
/**
* Configuration bits:
* bit[1:0]: Size of data (1,2,3 or 4 bytes). 1 Byte <=> b00
* bit[2]: Set this bit to 1 to abort a transfered packet
* bit[2]: Set this bit to 1 to abort a transferred packet
* bit[3]: Signals to VcInterface the start of a new telemetry packet
*/
static const uint32_t CONFIG_START = 0x8;
static constexpr uint32_t CONFIG_START = 0b00001000;
/**
* Abort a transferred packet.
*/
static constexpr uint32_t CONFIG_ABORT = 0b00000100;
/**
* Writing this word to the VcInterface base address signals to the virtual channel interface
* that a complete tm packet has been transferred.
*/
static const uint32_t CONFIG_END = 0x0;
static constexpr uint32_t CONFIG_END = 0x0;
/**
* Writing to this offset within the memory space of a virtual channel will insert data for
@ -72,7 +86,7 @@ class PapbVcInterface : public VcInterfaceIF {
std::string uioFile;
int mapNum = 0;
uint32_t* vcBaseReg = nullptr;
volatile uint32_t* vcBaseReg = nullptr;
uint32_t vcOffset = 0;
@ -82,11 +96,13 @@ class PapbVcInterface : public VcInterfaceIF {
*/
void startPacketTransfer();
void abortPacketTransfer();
/**
* @brief This function sends the config byte to the virtual channel interface of the PTME
* IP Core to signal the end of a packet transfer.
*/
void endPacketTransfer();
void completePacketTransfer();
/**
* @brief This function reads the papb busy signal indicating whether the virtual channel
@ -95,7 +111,7 @@ class PapbVcInterface : public VcInterfaceIF {
*
* @return returnvalue::OK when ready to receive data else PAPB_BUSY.
*/
ReturnValue_t pollPapbBusySignal();
ReturnValue_t pollPapbBusySignal(uint32_t maxPollRetries, uint32_t retryDelayUs) const;
/**
* @brief This function can be used for debugging to check whether there are packets in

View File

@ -20,7 +20,6 @@ ReturnValue_t Ptme::initialize() {
}
ReturnValue_t Ptme::writeToVc(uint8_t vcId, const uint8_t* data, size_t size) {
ReturnValue_t result = returnvalue::OK;
VcInterfaceMapIter vcInterfaceMapIter = vcInterfaceMap.find(vcId);
if (vcInterfaceMapIter == vcInterfaceMap.end()) {
sif::warning << "Ptme::writeToVc: No virtual channel interface found for the virtual "
@ -28,11 +27,10 @@ ReturnValue_t Ptme::writeToVc(uint8_t vcId, const uint8_t* data, size_t size) {
<< static_cast<unsigned int>(vcId) << std::endl;
return UNKNOWN_VC_ID;
}
result = vcInterfaceMapIter->second->write(data, size);
return result;
return vcInterfaceMapIter->second->write(data, size);
}
void Ptme::addVcInterface(VcId_t vcId, VcInterfaceIF* vc) {
void Ptme::addVcInterface(VcId_t vcId, VirtualChannelIF* vc) {
if (vcId > config::NUMBER_OF_VIRTUAL_CHANNELS) {
sif::warning << "Ptme::addVcInterface: Invalid virtual channel ID" << std::endl;
return;
@ -51,3 +49,22 @@ void Ptme::addVcInterface(VcId_t vcId, VcInterfaceIF* vc) {
return;
}
}
bool Ptme::isBusy(uint8_t vcId) const {
const auto& vcInterfaceMapIter = vcInterfaceMap.find(vcId);
if (vcInterfaceMapIter == vcInterfaceMap.end()) {
sif::warning << "Ptme::writeToVc: No virtual channel interface found for the virtual "
"channel with id "
<< static_cast<unsigned int>(vcId) << std::endl;
return UNKNOWN_VC_ID;
}
return vcInterfaceMapIter->second->isBusy();
}
void Ptme::cancelTransfer(uint8_t vcId) {
VcInterfaceMapIter vcInterfaceMapIter = vcInterfaceMap.find(vcId);
if (vcInterfaceMapIter == vcInterfaceMap.end()) {
return;
}
return vcInterfaceMapIter->second->cancelTransfer();
}

View File

@ -3,6 +3,7 @@
#include <fsfw_hal/common/gpio/gpioDefinitions.h>
#include <fsfw_hal/linux/gpio/LinuxLibgpioIF.h>
#include <linux/ipcore/VirtualChannelIF.h>
#include <cstring>
#include <unordered_map>
@ -10,13 +11,15 @@
#include "OBSWConfig.h"
#include "fsfw/returnvalues/returnvalue.h"
#include "linux/ipcore/PtmeIF.h"
#include "linux/ipcore/VcInterfaceIF.h"
/**
* @brief This class handles the interfacing to the telemetry (PTME) IP core responsible for the
* encoding of telemetry packets according to the CCSDS standards CCSDS 131.0-B-3 (TM
* Synchro- nization and channel coding) and CCSDS 132.0-B-2 (TM Space Data Link Protocoll). The IP
* cores are implemented on the programmable logic and are accessible through the linux UIO driver.
* @brief This class handles the interfacing to the telemetry (PTME) IP core.
*
* @details
* This module is responsible for the encoding of telemetry packets according to the CCSDS
* standards CCSDS 131.0-B-3 (TM Synchronization and channel coding) and CCSDS 132.0-B-2
* (TM Space Data Link Protocoll). The IP cores are implemented on the programmable logic and are
* accessible through the linux UIO driver.
*/
class Ptme : public PtmeIF, public SystemObject {
public:
@ -32,12 +35,14 @@ class Ptme : public PtmeIF, public SystemObject {
ReturnValue_t initialize() override;
ReturnValue_t writeToVc(uint8_t vcId, const uint8_t* data, size_t size) override;
bool isBusy(uint8_t vcId) const override;
void cancelTransfer(uint8_t vcId) override;
/**
* @brief This function adds the reference to a virtual channel interface to the vcInterface
* map.
*/
void addVcInterface(VcId_t vcId, VcInterfaceIF* vc);
void addVcInterface(VcId_t vcId, VirtualChannelIF* vc);
private:
static const uint8_t INTERFACE_ID = CLASS_ID::PTME;
@ -70,7 +75,7 @@ class Ptme : public PtmeIF, public SystemObject {
uint32_t* ptmeBaseAddress = nullptr;
using VcInterfaceMap = std::unordered_map<VcId_t, VcInterfaceIF*>;
using VcInterfaceMap = std::unordered_map<VcId_t, VirtualChannelIF*>;
using VcInterfaceMapIter = VcInterfaceMap::iterator;
VcInterfaceMap vcInterfaceMap;

View File

@ -48,3 +48,11 @@ ReturnValue_t PtmeConfig::configTxManipulator(bool enable) {
}
return result;
}
ReturnValue_t PtmeConfig::enableBatPriorityBit(bool enable) {
if (enable) {
return axiPtmeConfig->enableBatPriorityBit();
} else {
return axiPtmeConfig->disableBatPriorityBit();
}
}

View File

@ -1,6 +1,8 @@
#ifndef LINUX_OBC_PTMECONFIG_H_
#define LINUX_OBC_PTMECONFIG_H_
#include <fsfw_hal/common/gpio/gpioDefinitions.h>
#include "AxiPtmeConfig.h"
#include "fsfw/objectmanager/SystemObject.h"
#include "fsfw/returnvalues/returnvalue.h"
@ -53,6 +55,15 @@ class PtmeConfig : public SystemObject {
*/
ReturnValue_t configTxManipulator(bool enable);
/**
* Enable the bat priority bit in the PTME wrapper component.
* Please note that a reset of the PTME is still required as specified in the documentation.
* This is done by a higher level component.
* @param enable
* @return
*/
ReturnValue_t enableBatPriorityBit(bool enable);
private:
static const uint8_t INTERFACE_ID = CLASS_ID::RATE_SETTER;

View File

@ -22,6 +22,8 @@ class PtmeIF {
* @param size Number of bytes to write
*/
virtual ReturnValue_t writeToVc(uint8_t vcId, const uint8_t* data, size_t size) = 0;
virtual bool isBusy(uint8_t vcId) const = 0;
virtual void cancelTransfer(uint8_t vcId) = 0;
};
#endif /* LINUX_OBC_PTMEIF_H_ */

View File

@ -1,6 +1,7 @@
#ifndef LINUX_OBC_VCINTERFACEIF_H_
#define LINUX_OBC_VCINTERFACEIF_H_
#include <mission/tmtc/DirectTmSinkIF.h>
#include <stddef.h>
#include "fsfw/returnvalues/returnvalue.h"
@ -8,23 +9,16 @@
/**
* @brief Interface class for managing different virtual channels of the PTME IP core implemented
* in the programmable logic.
*
* @details
* Also implements @DirectTmSinkIF to allow wiriting to the VC directly.
* @author J. Meier
*/
class VcInterfaceIF {
class VirtualChannelIF : public DirectTmSinkIF {
public:
virtual ~VcInterfaceIF(){};
/**
* @brief Implememts the functionality to write data in the virtual channel of the PTME IP
* Core.
*
* @param data Pointer to buffer holding the data to write
* @param size Number of bytes to write
*/
virtual ReturnValue_t write(const uint8_t* data, size_t size) = 0;
virtual ~VirtualChannelIF(){};
virtual ReturnValue_t initialize() = 0;
virtual void cancelTransfer() = 0;
};
#endif /* LINUX_OBC_VCINTERFACEIF_H_ */

View File

@ -8,6 +8,9 @@
#include "ObjectFactory.h"
#include "eive/objects.h"
PosixThreadArgs scheduling::RR_SCHEDULING = {.policy = SchedulingPolicy::RR};
PosixThreadArgs scheduling::NORMAL_SCHEDULING;
void scheduling::scheduleScexReader(TaskFactory& factory, PeriodicTaskIF*& scexReaderTask) {
using namespace scheduling;
ReturnValue_t result = returnvalue::OK;
@ -18,8 +21,9 @@ void scheduling::scheduleScexReader(TaskFactory& factory, PeriodicTaskIF*& scexR
#endif
result = returnvalue::OK;
scexReaderTask = factory.createPeriodicTask(
"SCEX_UART_READER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0, missedDeadlineFunc);
scexReaderTask =
factory.createPeriodicTask("SCEX_UART_READER", 20, PeriodicTaskIF::MINIMUM_STACK_SIZE, 2.0,
missedDeadlineFunc, &NORMAL_SCHEDULING);
result = scexReaderTask->addComponent(objects::SCEX_UART_READER);
if (result != returnvalue::OK) {
printAddObjectError("SCEX_UART_READER", objects::SCEX_UART_READER);
@ -27,7 +31,6 @@ void scheduling::scheduleScexReader(TaskFactory& factory, PeriodicTaskIF*& scexR
}
void scheduling::addMpsocSupvHandlers(PeriodicTaskIF* plTask) {
#if OBSW_ADD_PLOC_SUPERVISOR == 1
plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::PERFORM_OPERATION);
plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::SEND_WRITE);
plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::GET_WRITE);
@ -35,9 +38,7 @@ void scheduling::addMpsocSupvHandlers(PeriodicTaskIF* plTask) {
plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::GET_READ);
plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::SEND_READ);
plTask->addComponent(objects::PLOC_SUPERVISOR_HANDLER, DeviceHandlerIF::GET_READ);
#endif
#if OBSW_ADD_PLOC_MPSOC == 1
plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::PERFORM_OPERATION);
plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::SEND_WRITE);
plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::GET_WRITE);
@ -45,7 +46,6 @@ void scheduling::addMpsocSupvHandlers(PeriodicTaskIF* plTask) {
plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::GET_READ);
plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::SEND_READ);
plTask->addComponent(objects::PLOC_MPSOC_HANDLER, DeviceHandlerIF::GET_READ);
#endif
}
void scheduling::scheduleScexDev(PeriodicTaskIF*& scexDevHandler) {

View File

@ -1,8 +1,13 @@
#pragma once
#include <fsfw/osal/linux/PosixThread.h>
#include <fsfw/tasks/TaskFactory.h>
namespace scheduling {
extern PosixThreadArgs RR_SCHEDULING;
extern PosixThreadArgs NORMAL_SCHEDULING;
void scheduleScexDev(PeriodicTaskIF*& scexDevHandler);
void scheduleScexReader(TaskFactory& factory, PeriodicTaskIF*& scexReaderTask);
void addMpsocSupvHandlers(PeriodicTaskIF* task);