Update FSFW #24

Merged
muellerr merged 160 commits from mueller/master into master 2021-09-26 22:54:37 +02:00
52 changed files with 2404 additions and 405 deletions

View File

@ -26,7 +26,8 @@ enum GpioOperation {
enum GpioTypes {
NONE,
GPIO_REGULAR,
GPIO_REGULAR_BY_CHIP,
GPIO_REGULAR_BY_LABEL,
CALLBACK
};
@ -68,28 +69,57 @@ public:
int initValue = 0;
};
class GpiodRegular: public GpioBase {
class GpiodRegularBase: public GpioBase {
public:
GpiodRegular() :
GpioBase(gpio::GpioTypes::GPIO_REGULAR, std::string(), gpio::Direction::IN, 0) {
GpiodRegularBase(gpio::GpioTypes gpioType, std::string consumer, gpio::Direction direction,
int initValue, int lineNum): GpioBase(gpioType, consumer, direction, initValue),
lineNum(lineNum) {
}
;
GpiodRegular(std::string chipname_, int lineNum_, std::string consumer_,
gpio::Direction direction_, int initValue_) :
GpioBase(gpio::GpioTypes::GPIO_REGULAR, consumer_, direction_, initValue_),
chipname(chipname_), lineNum(lineNum_) {
}
GpiodRegular(std::string chipname_, int lineNum_, std::string consumer_) :
GpioBase(gpio::GpioTypes::GPIO_REGULAR, consumer_, gpio::Direction::IN, 0),
chipname(chipname_), lineNum(lineNum_) {
}
std::string chipname;
int lineNum = 0;
struct gpiod_line* lineHandle = nullptr;
};
class GpiodRegularByChip: public GpiodRegularBase {
public:
GpiodRegularByChip() :
GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP,
std::string(), gpio::Direction::IN, gpio::LOW, 0) {
}
GpiodRegularByChip(std::string chipname_, int lineNum_, std::string consumer_,
gpio::Direction direction_, int initValue_) :
GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP,
consumer_, direction_, initValue_, lineNum_),
chipname(chipname_){
}
GpiodRegularByChip(std::string chipname_, int lineNum_, std::string consumer_) :
GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP, consumer_,
gpio::Direction::IN, gpio::LOW, lineNum_),
chipname(chipname_) {
}
std::string chipname;
};
class GpiodRegularByLabel: public GpiodRegularBase {
public:
GpiodRegularByLabel(std::string label_, int lineNum_, std::string consumer_,
gpio::Direction direction_, int initValue_) :
GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL, consumer_,
direction_, initValue_, lineNum_),
label(label_) {
}
GpiodRegularByLabel(std::string label_, int lineNum_, std::string consumer_) :
GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL, consumer_,
gpio::Direction::IN, gpio::LOW, lineNum_),
label(label_) {
}
std::string label;
};
class GpioCallback: public GpioBase {
public:
GpioCallback(std::string consumer, gpio::Direction direction_, int initValue_,

View File

@ -1,3 +1,5 @@
target_sources(${LIB_FSFW_NAME} PRIVATE
GyroL3GD20Handler.cpp
MgmRM3100Handler.cpp
MgmLIS3MDLHandler.cpp
)

View File

@ -1,13 +1,15 @@
#include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h"
#include "GyroL3GD20Handler.h"
#include "fsfw/datapool/PoolReadGuard.h"
#include <cmath>
GyroHandlerL3GD20H::GyroHandlerL3GD20H(object_id_t objectId, object_id_t deviceCommunication,
CookieIF *comCookie):
CookieIF *comCookie, uint32_t transitionDelayMs):
DeviceHandlerBase(objectId, deviceCommunication, comCookie),
dataset(this) {
transitionDelayMs(transitionDelayMs), dataset(this) {
#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1
debugDivider = new PeriodicOperationDivider(5);
debugDivider = new PeriodicOperationDivider(3);
#endif
}
@ -47,7 +49,7 @@ ReturnValue_t GyroHandlerL3GD20H::buildTransitionDeviceCommand(DeviceCommandId_t
switch(internalState) {
case(InternalState::NONE):
case(InternalState::NORMAL): {
return HasReturnvaluesIF::RETURN_OK;
return NOTHING_TO_SEND;
}
case(InternalState::CONFIGURE): {
*id = L3GD20H::CONFIGURE_CTRL_REGS;
@ -66,10 +68,11 @@ ReturnValue_t GyroHandlerL3GD20H::buildTransitionDeviceCommand(DeviceCommandId_t
default:
#if FSFW_CPP_OSTREAM_ENABLED == 1
/* Might be a configuration error. */
sif::debug << "GyroHandler::buildTransitionDeviceCommand: Unknown internal state!" <<
std::endl;
sif::warning << "GyroL3GD20Handler::buildTransitionDeviceCommand: "
"Unknown internal state!" << std::endl;
#else
sif::printDebug("GyroHandler::buildTransitionDeviceCommand: Unknown internal state!\n");
sif::printDebug("GyroL3GD20Handler::buildTransitionDeviceCommand: "
"Unknown internal state!\n");
#endif
return HasReturnvaluesIF::RETURN_OK;
}
@ -144,7 +147,7 @@ ReturnValue_t GyroHandlerL3GD20H::buildCommandFromCommand(
ReturnValue_t GyroHandlerL3GD20H::scanForReply(const uint8_t *start, size_t len,
DeviceCommandId_t *foundId, size_t *foundLen) {
/* For SPI, the ID will always be the one of the last sent command. */
// For SPI, the ID will always be the one of the last sent command
*foundId = this->getPendingCommand();
*foundLen = this->rawPacketLen;
@ -166,7 +169,7 @@ ReturnValue_t GyroHandlerL3GD20H::interpretDeviceReply(DeviceCommandId_t id,
commandExecuted = true;
}
else {
/* Attempt reconfiguration. */
// Attempt reconfiguration
internalState = InternalState::CONFIGURE;
return DeviceHandlerIF::DEVICE_REPLY_INVALID;
}
@ -199,13 +202,12 @@ ReturnValue_t GyroHandlerL3GD20H::interpretDeviceReply(DeviceCommandId_t id,
if(debugDivider->checkAndIncrement()) {
/* Set terminal to utf-8 if there is an issue with micro printout. */
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::info << "GyroHandlerL3GD20H: Angular velocities in degrees per second:" <<
std::endl;
sif::info << "X: " << angVelocX << " \xC2\xB0" << std::endl;
sif::info << "Y: " << angVelocY << " \xC2\xB0" << std::endl;
sif::info << "Z: " << angVelocZ << " \xC2\xB0" << std::endl;
sif::info << "GyroHandlerL3GD20H: Angular velocities (deg/s):" << std::endl;
sif::info << "X: " << angVelocX << std::endl;
sif::info << "Y: " << angVelocY << std::endl;
sif::info << "Z: " << angVelocZ << std::endl;
#else
sif::printInfo("GyroHandlerL3GD20H: Angular velocities in degrees per second:\n");
sif::printInfo("GyroHandlerL3GD20H: Angular velocities (deg/s):\n");
sif::printInfo("X: %f\n", angVelocX);
sif::printInfo("Y: %f\n", angVelocY);
sif::printInfo("Z: %f\n", angVelocZ);
@ -215,11 +217,32 @@ ReturnValue_t GyroHandlerL3GD20H::interpretDeviceReply(DeviceCommandId_t id,
PoolReadGuard readSet(&dataset);
if(readSet.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
dataset.angVelocX = angVelocX;
dataset.angVelocY = angVelocY;
dataset.angVelocZ = angVelocZ;
if(std::abs(angVelocX) < this->absLimitX) {
dataset.angVelocX = angVelocX;
dataset.angVelocX.setValid(true);
}
else {
dataset.angVelocX.setValid(false);
}
if(std::abs(angVelocY) < this->absLimitY) {
dataset.angVelocY = angVelocY;
dataset.angVelocY.setValid(true);
}
else {
dataset.angVelocY.setValid(false);
}
if(std::abs(angVelocZ) < this->absLimitZ) {
dataset.angVelocZ = angVelocZ;
dataset.angVelocZ.setValid(true);
}
else {
dataset.angVelocZ.setValid(false);
}
dataset.temperature = temperature;
dataset.setValidity(true, true);
dataset.temperature.setValid(true);
}
break;
}
@ -231,23 +254,19 @@ ReturnValue_t GyroHandlerL3GD20H::interpretDeviceReply(DeviceCommandId_t id,
uint32_t GyroHandlerL3GD20H::getTransitionDelayMs(Mode_t from, Mode_t to) {
return 10000;
return this->transitionDelayMs;
}
void GyroHandlerL3GD20H::setGoNormalModeAtStartup() {
void GyroHandlerL3GD20H::setToGoToNormalMode(bool enable) {
this->goNormalModeImmediately = true;
}
ReturnValue_t GyroHandlerL3GD20H::initializeLocalDataPool(
localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) {
localDataPoolMap.emplace(L3GD20H::ANG_VELOC_X,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Y,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Z,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(L3GD20H::TEMPERATURE,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(L3GD20H::ANG_VELOC_X, new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Y, new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(L3GD20H::ANG_VELOC_Z, new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(L3GD20H::TEMPERATURE, new PoolEntry<float>({0.0}));
return HasReturnvaluesIF::RETURN_OK;
}
@ -260,3 +279,9 @@ void GyroHandlerL3GD20H::fillCommandAndReplyMap() {
void GyroHandlerL3GD20H::modeChanged() {
internalState = InternalState::NONE;
}
void GyroHandlerL3GD20H::setAbsoluteLimits(float limitX, float limitY, float limitZ) {
this->absLimitX = limitX;
this->absLimitY = limitY;
this->absLimitZ = limitZ;
}

View File

@ -7,10 +7,6 @@
#include <fsfw/devicehandlers/DeviceHandlerBase.h>
#include <fsfw/globalfunctions/PeriodicOperationDivider.h>
#ifndef FSFW_HAL_L3GD20_GYRO_DEBUG
#define FSFW_HAL_L3GD20_GYRO_DEBUG 0
#endif /* FSFW_HAL_L3GD20_GYRO_DEBUG */
/**
* @brief Device Handler for the L3GD20H gyroscope sensor
* (https://www.st.com/en/mems-and-sensors/l3gd20h.html)
@ -23,10 +19,22 @@
class GyroHandlerL3GD20H: public DeviceHandlerBase {
public:
GyroHandlerL3GD20H(object_id_t objectId, object_id_t deviceCommunication,
CookieIF* comCookie);
CookieIF* comCookie, uint32_t transitionDelayMs);
virtual ~GyroHandlerL3GD20H();
void setGoNormalModeAtStartup();
/**
* Set the absolute limit for the values on the axis in degrees per second.
* The dataset values will be marked as invalid if that limit is exceeded
* @param xLimit
* @param yLimit
* @param zLimit
*/
void setAbsoluteLimits(float limitX, float limitY, float limitZ);
/**
* @brief Configure device handler to go to normal mode immediately
*/
void setToGoToNormalMode(bool enable);
protected:
/* DeviceHandlerBase overrides */
@ -41,18 +49,23 @@ protected:
size_t commandDataLen) override;
ReturnValue_t scanForReply(const uint8_t *start, size_t len,
DeviceCommandId_t *foundId, size_t *foundLen) override;
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id,
virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id,
const uint8_t *packet) override;
void fillCommandAndReplyMap() override;
void modeChanged() override;
uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override;
virtual uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override;
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) override;
private:
uint32_t transitionDelayMs = 0;
GyroPrimaryDataset dataset;
float absLimitX = L3GD20H::RANGE_DPS_00;
float absLimitY = L3GD20H::RANGE_DPS_00;
float absLimitZ = L3GD20H::RANGE_DPS_00;
enum class InternalState {
NONE,
CONFIGURE,

View File

@ -0,0 +1,520 @@
#include "MgmLIS3MDLHandler.h"
#include "fsfw/datapool/PoolReadGuard.h"
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
#include "fsfw/globalfunctions/PeriodicOperationDivider.h"
#endif
#include <cmath>
MgmLIS3MDLHandler::MgmLIS3MDLHandler(object_id_t objectId, object_id_t deviceCommunication,
CookieIF* comCookie, uint32_t transitionDelay):
DeviceHandlerBase(objectId, deviceCommunication, comCookie),
dataset(this), transitionDelay(transitionDelay) {
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
debugDivider = new PeriodicOperationDivider(3);
#endif
// Set to default values right away
registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT;
registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT;
registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT;
registers[3] = MGMLIS3MDL::CTRL_REG4_DEFAULT;
registers[4] = MGMLIS3MDL::CTRL_REG5_DEFAULT;
}
MgmLIS3MDLHandler::~MgmLIS3MDLHandler() {
}
void MgmLIS3MDLHandler::doStartUp() {
switch (internalState) {
case(InternalState::STATE_NONE): {
internalState = InternalState::STATE_FIRST_CONTACT;
break;
}
case(InternalState::STATE_FIRST_CONTACT): {
/* Will be set by checking device ID (WHO AM I register) */
if(commandExecuted) {
commandExecuted = false;
internalState = InternalState::STATE_SETUP;
}
break;
}
case(InternalState::STATE_SETUP): {
internalState = InternalState::STATE_CHECK_REGISTERS;
break;
}
case(InternalState::STATE_CHECK_REGISTERS): {
/* Set up cached registers which will be used to configure the MGM. */
if(commandExecuted) {
commandExecuted = false;
if(goToNormalMode) {
setMode(MODE_NORMAL);
}
else {
setMode(_MODE_TO_ON);
}
}
break;
}
default:
break;
}
}
void MgmLIS3MDLHandler::doShutDown() {
setMode(_MODE_POWER_DOWN);
}
ReturnValue_t MgmLIS3MDLHandler::buildTransitionDeviceCommand(
DeviceCommandId_t *id) {
switch (internalState) {
case(InternalState::STATE_NONE):
case(InternalState::STATE_NORMAL): {
return HasReturnvaluesIF::RETURN_OK;
}
case(InternalState::STATE_FIRST_CONTACT): {
*id = MGMLIS3MDL::IDENTIFY_DEVICE;
break;
}
case(InternalState::STATE_SETUP): {
*id = MGMLIS3MDL::SETUP_MGM;
break;
}
case(InternalState::STATE_CHECK_REGISTERS): {
*id = MGMLIS3MDL::READ_CONFIG_AND_DATA;
break;
}
default: {
/* might be a configuration error. */
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "GyroHandler::buildTransitionDeviceCommand: Unknown internal state!" <<
std::endl;
#else
sif::printWarning("GyroHandler::buildTransitionDeviceCommand: Unknown internal state!\n");
#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */
return HasReturnvaluesIF::RETURN_OK;
}
}
return buildCommandFromCommand(*id, NULL, 0);
}
uint8_t MgmLIS3MDLHandler::readCommand(uint8_t command, bool continuousCom) {
command |= (1 << MGMLIS3MDL::RW_BIT);
if (continuousCom == true) {
command |= (1 << MGMLIS3MDL::MS_BIT);
}
return command;
}
uint8_t MgmLIS3MDLHandler::writeCommand(uint8_t command, bool continuousCom) {
command &= ~(1 << MGMLIS3MDL::RW_BIT);
if (continuousCom == true) {
command |= (1 << MGMLIS3MDL::MS_BIT);
}
return command;
}
void MgmLIS3MDLHandler::setupMgm() {
registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT;
registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT;
registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT;
registers[3] = MGMLIS3MDL::CTRL_REG4_DEFAULT;
registers[4] = MGMLIS3MDL::CTRL_REG5_DEFAULT;
prepareCtrlRegisterWrite();
}
ReturnValue_t MgmLIS3MDLHandler::buildNormalDeviceCommand(
DeviceCommandId_t *id) {
// Data/config register will be read in an alternating manner.
if(communicationStep == CommunicationStep::DATA) {
*id = MGMLIS3MDL::READ_CONFIG_AND_DATA;
communicationStep = CommunicationStep::TEMPERATURE;
return buildCommandFromCommand(*id, NULL, 0);
}
else {
*id = MGMLIS3MDL::READ_TEMPERATURE;
communicationStep = CommunicationStep::DATA;
return buildCommandFromCommand(*id, NULL, 0);
}
}
ReturnValue_t MgmLIS3MDLHandler::buildCommandFromCommand(
DeviceCommandId_t deviceCommand, const uint8_t *commandData,
size_t commandDataLen) {
switch(deviceCommand) {
case(MGMLIS3MDL::READ_CONFIG_AND_DATA): {
std::memset(commandBuffer, 0, sizeof(commandBuffer));
commandBuffer[0] = readCommand(MGMLIS3MDL::CTRL_REG1, true);
rawPacket = commandBuffer;
rawPacketLen = MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1;
return RETURN_OK;
}
case(MGMLIS3MDL::READ_TEMPERATURE): {
std::memset(commandBuffer, 0, 3);
commandBuffer[0] = readCommand(MGMLIS3MDL::TEMP_LOWBYTE, true);
rawPacket = commandBuffer;
rawPacketLen = 3;
return RETURN_OK;
}
case(MGMLIS3MDL::IDENTIFY_DEVICE): {
return identifyDevice();
}
case(MGMLIS3MDL::TEMP_SENSOR_ENABLE): {
return enableTemperatureSensor(commandData, commandDataLen);
}
case(MGMLIS3MDL::SETUP_MGM): {
setupMgm();
return HasReturnvaluesIF::RETURN_OK;
}
case(MGMLIS3MDL::ACCURACY_OP_MODE_SET): {
return setOperatingMode(commandData, commandDataLen);
}
default:
return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED;
}
return HasReturnvaluesIF::RETURN_FAILED;
}
ReturnValue_t MgmLIS3MDLHandler::identifyDevice() {
uint32_t size = 2;
commandBuffer[0] = readCommand(MGMLIS3MDL::IDENTIFY_DEVICE_REG_ADDR);
commandBuffer[1] = 0x00;
rawPacket = commandBuffer;
rawPacketLen = size;
return RETURN_OK;
}
ReturnValue_t MgmLIS3MDLHandler::scanForReply(const uint8_t *start,
size_t len, DeviceCommandId_t *foundId, size_t *foundLen) {
*foundLen = len;
if (len == MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1) {
*foundLen = len;
*foundId = MGMLIS3MDL::READ_CONFIG_AND_DATA;
// Check validity by checking config registers
if (start[1] != registers[0] or start[2] != registers[1] or
start[3] != registers[2] or start[4] != registers[3] or
start[5] != registers[4]) {
#if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "MGMHandlerLIS3MDL::scanForReply: Invalid registers!" << std::endl;
#else
sif::printWarning("MGMHandlerLIS3MDL::scanForReply: Invalid registers!\n");
#endif
#endif
return DeviceHandlerIF::INVALID_DATA;
}
if(mode == _MODE_START_UP) {
commandExecuted = true;
}
}
else if(len == MGMLIS3MDL::TEMPERATURE_REPLY_LEN) {
*foundLen = len;
*foundId = MGMLIS3MDL::READ_TEMPERATURE;
}
else if (len == MGMLIS3MDL::SETUP_REPLY_LEN) {
*foundLen = len;
*foundId = MGMLIS3MDL::SETUP_MGM;
}
else if (len == SINGLE_COMMAND_ANSWER_LEN) {
*foundLen = len;
*foundId = getPendingCommand();
if(*foundId == MGMLIS3MDL::IDENTIFY_DEVICE) {
if(start[1] != MGMLIS3MDL::DEVICE_ID) {
#if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "MGMHandlerLIS3MDL::scanForReply: "
"Device identification failed!" << std::endl;
#else
sif::printWarning("MGMHandlerLIS3MDL::scanForReply: "
"Device identification failed!\n");
#endif
#endif
return DeviceHandlerIF::INVALID_DATA;
}
if(mode == _MODE_START_UP) {
commandExecuted = true;
}
}
}
else {
return DeviceHandlerIF::INVALID_DATA;
}
/* Data with SPI Interface always has this answer */
if (start[0] == 0b11111111) {
return RETURN_OK;
}
else {
return DeviceHandlerIF::INVALID_DATA;
}
}
ReturnValue_t MgmLIS3MDLHandler::interpretDeviceReply(DeviceCommandId_t id,
const uint8_t *packet) {
switch (id) {
case MGMLIS3MDL::IDENTIFY_DEVICE: {
break;
}
case MGMLIS3MDL::SETUP_MGM: {
break;
}
case MGMLIS3MDL::READ_CONFIG_AND_DATA: {
// TODO: Store configuration in new local datasets.
float sensitivityFactor = getSensitivityFactor(getSensitivity(registers[2]));
int16_t mgmMeasurementRawX = packet[MGMLIS3MDL::X_HIGHBYTE_IDX] << 8
| packet[MGMLIS3MDL::X_LOWBYTE_IDX] ;
int16_t mgmMeasurementRawY = packet[MGMLIS3MDL::Y_HIGHBYTE_IDX] << 8
| packet[MGMLIS3MDL::Y_LOWBYTE_IDX] ;
int16_t mgmMeasurementRawZ = packet[MGMLIS3MDL::Z_HIGHBYTE_IDX] << 8
| packet[MGMLIS3MDL::Z_LOWBYTE_IDX] ;
/* Target value in microtesla */
float mgmX = static_cast<float>(mgmMeasurementRawX) * sensitivityFactor
* MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR;
float mgmY = static_cast<float>(mgmMeasurementRawY) * sensitivityFactor
* MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR;
float mgmZ = static_cast<float>(mgmMeasurementRawZ) * sensitivityFactor
* MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR;
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
if(debugDivider->checkAndIncrement()) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::info << "MGMHandlerLIS3: Magnetic field strength in"
" microtesla:" << std::endl;
sif::info << "X: " << mgmX << " uT" << std::endl;
sif::info << "Y: " << mgmY << " uT" << std::endl;
sif::info << "Z: " << mgmZ << " uT" << std::endl;
#else
sif::printInfo("MGMHandlerLIS3: Magnetic field strength in microtesla:\n");
sif::printInfo("X: %f uT\n", mgmX);
sif::printInfo("Y: %f uT\n", mgmY);
sif::printInfo("Z: %f uT\n", mgmZ);
#endif /* FSFW_CPP_OSTREAM_ENABLED == 0 */
}
#endif /* OBSW_VERBOSE_LEVEL >= 1 */
PoolReadGuard readHelper(&dataset);
if(readHelper.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
if(std::abs(mgmX) < absLimitX) {
dataset.fieldStrengthX = mgmX;
dataset.fieldStrengthX.setValid(true);
}
else {
dataset.fieldStrengthX.setValid(false);
}
if(std::abs(mgmY) < absLimitY) {
dataset.fieldStrengthY = mgmY;
dataset.fieldStrengthY.setValid(true);
}
else {
dataset.fieldStrengthY.setValid(false);
}
if(std::abs(mgmZ) < absLimitZ) {
dataset.fieldStrengthZ = mgmZ;
dataset.fieldStrengthZ.setValid(true);
}
else {
dataset.fieldStrengthZ.setValid(false);
}
}
break;
}
case MGMLIS3MDL::READ_TEMPERATURE: {
int16_t tempValueRaw = packet[2] << 8 | packet[1];
float tempValue = 25.0 + ((static_cast<float>(tempValueRaw)) / 8.0);
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
if(debugDivider->check()) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::info << "MGMHandlerLIS3: Temperature: " << tempValue << " C" <<
std::endl;
#else
sif::printInfo("MGMHandlerLIS3: Temperature: %f C\n");
#endif
}
#endif
ReturnValue_t result = dataset.read();
if(result == HasReturnvaluesIF::RETURN_OK) {
dataset.temperature = tempValue;
dataset.commit();
}
break;
}
default: {
return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY;
}
}
return RETURN_OK;
}
MGMLIS3MDL::Sensitivies MgmLIS3MDLHandler::getSensitivity(uint8_t ctrlRegister2) {
bool fs0Set = ctrlRegister2 & (1 << MGMLIS3MDL::FSO); // Checks if FS0 bit is set
bool fs1Set = ctrlRegister2 & (1 << MGMLIS3MDL::FS1); // Checks if FS1 bit is set
if (fs0Set && fs1Set)
return MGMLIS3MDL::Sensitivies::GAUSS_16;
else if (!fs0Set && fs1Set)
return MGMLIS3MDL::Sensitivies::GAUSS_12;
else if (fs0Set && !fs1Set)
return MGMLIS3MDL::Sensitivies::GAUSS_8;
else
return MGMLIS3MDL::Sensitivies::GAUSS_4;
}
float MgmLIS3MDLHandler::getSensitivityFactor(MGMLIS3MDL::Sensitivies sens) {
switch(sens) {
case(MGMLIS3MDL::GAUSS_4): {
return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_4_SENS;
}
case(MGMLIS3MDL::GAUSS_8): {
return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_8_SENS;
}
case(MGMLIS3MDL::GAUSS_12): {
return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_12_SENS;
}
case(MGMLIS3MDL::GAUSS_16): {
return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_16_SENS;
}
default: {
// Should never happen
return MGMLIS3MDL::FIELD_LSB_PER_GAUSS_4_SENS;
}
}
}
ReturnValue_t MgmLIS3MDLHandler::enableTemperatureSensor(
const uint8_t *commandData, size_t commandDataLen) {
triggerEvent(CHANGE_OF_SETUP_PARAMETER);
uint32_t size = 2;
commandBuffer[0] = writeCommand(MGMLIS3MDL::CTRL_REG1);
if (commandDataLen > 1) {
return INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS;
}
switch (*commandData) {
case (MGMLIS3MDL::ON): {
commandBuffer[1] = registers[0] | (1 << 7);
break;
}
case (MGMLIS3MDL::OFF): {
commandBuffer[1] = registers[0] & ~(1 << 7);
break;
}
default:
return INVALID_COMMAND_PARAMETER;
}
registers[0] = commandBuffer[1];
rawPacket = commandBuffer;
rawPacketLen = size;
return RETURN_OK;
}
ReturnValue_t MgmLIS3MDLHandler::setOperatingMode(const uint8_t *commandData,
size_t commandDataLen) {
triggerEvent(CHANGE_OF_SETUP_PARAMETER);
if (commandDataLen != 1) {
return INVALID_NUMBER_OR_LENGTH_OF_PARAMETERS;
}
switch (commandData[0]) {
case MGMLIS3MDL::LOW:
registers[0] = (registers[0] & (~(1 << MGMLIS3MDL::OM1))) & (~(1 << MGMLIS3MDL::OM0));
registers[3] = (registers[3] & (~(1 << MGMLIS3MDL::OMZ1))) & (~(1 << MGMLIS3MDL::OMZ0));
break;
case MGMLIS3MDL::MEDIUM:
registers[0] = (registers[0] & (~(1 << MGMLIS3MDL::OM1))) | (1 << MGMLIS3MDL::OM0);
registers[3] = (registers[3] & (~(1 << MGMLIS3MDL::OMZ1))) | (1 << MGMLIS3MDL::OMZ0);
break;
case MGMLIS3MDL::HIGH:
registers[0] = (registers[0] | (1 << MGMLIS3MDL::OM1)) & (~(1 << MGMLIS3MDL::OM0));
registers[3] = (registers[3] | (1 << MGMLIS3MDL::OMZ1)) & (~(1 << MGMLIS3MDL::OMZ0));
break;
case MGMLIS3MDL::ULTRA:
registers[0] = (registers[0] | (1 << MGMLIS3MDL::OM1)) | (1 << MGMLIS3MDL::OM0);
registers[3] = (registers[3] | (1 << MGMLIS3MDL::OMZ1)) | (1 << MGMLIS3MDL::OMZ0);
break;
default:
break;
}
return prepareCtrlRegisterWrite();
}
void MgmLIS3MDLHandler::fillCommandAndReplyMap() {
insertInCommandAndReplyMap(MGMLIS3MDL::READ_CONFIG_AND_DATA, 1, &dataset);
insertInCommandAndReplyMap(MGMLIS3MDL::READ_TEMPERATURE, 1);
insertInCommandAndReplyMap(MGMLIS3MDL::SETUP_MGM, 1);
insertInCommandAndReplyMap(MGMLIS3MDL::IDENTIFY_DEVICE, 1);
insertInCommandAndReplyMap(MGMLIS3MDL::TEMP_SENSOR_ENABLE, 1);
insertInCommandAndReplyMap(MGMLIS3MDL::ACCURACY_OP_MODE_SET, 1);
}
void MgmLIS3MDLHandler::setToGoToNormalMode(bool enable) {
this->goToNormalMode = enable;
}
ReturnValue_t MgmLIS3MDLHandler::prepareCtrlRegisterWrite() {
commandBuffer[0] = writeCommand(MGMLIS3MDL::CTRL_REG1, true);
for (size_t i = 0; i < MGMLIS3MDL::NR_OF_CTRL_REGISTERS; i++) {
commandBuffer[i + 1] = registers[i];
}
rawPacket = commandBuffer;
rawPacketLen = MGMLIS3MDL::NR_OF_CTRL_REGISTERS + 1;
// We dont have to check if this is working because we just did i
return RETURN_OK;
}
void MgmLIS3MDLHandler::doTransition(Mode_t modeFrom, Submode_t subModeFrom) {
}
uint32_t MgmLIS3MDLHandler::getTransitionDelayMs(Mode_t from, Mode_t to) {
return transitionDelay;
}
void MgmLIS3MDLHandler::modeChanged(void) {
internalState = InternalState::STATE_NONE;
}
ReturnValue_t MgmLIS3MDLHandler::initializeLocalDataPool(
localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) {
localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_X,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_Y,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(MGMLIS3MDL::FIELD_STRENGTH_Z,
new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(MGMLIS3MDL::TEMPERATURE_CELCIUS,
new PoolEntry<float>({0.0}));
return HasReturnvaluesIF::RETURN_OK;
}
void MgmLIS3MDLHandler::setAbsoluteLimits(float xLimit, float yLimit, float zLimit) {
this->absLimitX = xLimit;
this->absLimitY = yLimit;
this->absLimitZ = zLimit;
}

View File

@ -0,0 +1,186 @@
#ifndef MISSION_DEVICES_MGMLIS3MDLHANDLER_H_
#define MISSION_DEVICES_MGMLIS3MDLHANDLER_H_
#include "fsfw/FSFW.h"
#include "events/subsystemIdRanges.h"
#include "devicedefinitions/MgmLIS3HandlerDefs.h"
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
class PeriodicOperationDivider;
/**
* @brief Device handler object for the LIS3MDL 3-axis magnetometer
* by STMicroeletronics
* @details
* Datasheet can be found online by googling LIS3MDL.
* Flight manual:
* https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/LIS3MDL_MGM
* @author L. Loidold, R. Mueller
*/
class MgmLIS3MDLHandler: public DeviceHandlerBase {
public:
enum class CommunicationStep {
DATA,
TEMPERATURE
};
static const uint8_t INTERFACE_ID = CLASS_ID::MGM_LIS3MDL;
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::MGM_LIS3MDL;
//Notifies a command to change the setup parameters
static const Event CHANGE_OF_SETUP_PARAMETER = MAKE_EVENT(0, severity::LOW);
MgmLIS3MDLHandler(uint32_t objectId, object_id_t deviceCommunication, CookieIF* comCookie,
uint32_t transitionDelay);
virtual ~MgmLIS3MDLHandler();
/**
* Set the absolute limit for the values on the axis in microtesla. The dataset values will
* be marked as invalid if that limit is exceeded
* @param xLimit
* @param yLimit
* @param zLimit
*/
void setAbsoluteLimits(float xLimit, float yLimit, float zLimit);
void setToGoToNormalMode(bool enable);
protected:
/** DeviceHandlerBase overrides */
void doShutDown() override;
void doStartUp() override;
void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override;
virtual uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override;
ReturnValue_t buildCommandFromCommand(
DeviceCommandId_t deviceCommand, const uint8_t *commandData,
size_t commandDataLen) override;
ReturnValue_t buildTransitionDeviceCommand(
DeviceCommandId_t *id) override;
ReturnValue_t buildNormalDeviceCommand(
DeviceCommandId_t *id) override;
ReturnValue_t scanForReply(const uint8_t *start, size_t len,
DeviceCommandId_t *foundId, size_t *foundLen) override;
/**
* This implementation is tailored towards space applications and will flag values larger
* than 100 microtesla on X,Y and 150 microtesla on Z as invalid
* @param id
* @param packet
* @return
*/
virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id,
const uint8_t *packet) override;
void fillCommandAndReplyMap() override;
void modeChanged(void) override;
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) override;
private:
MGMLIS3MDL::MgmPrimaryDataset dataset;
//Length a single command SPI answer
static const uint8_t SINGLE_COMMAND_ANSWER_LEN = 2;
uint32_t transitionDelay;
// Single SPI command has 2 bytes, first for adress, second for content
size_t singleComandSize = 2;
// Has the size for all adresses of the lis3mdl + the continous write bit
uint8_t commandBuffer[MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1];
float absLimitX = 100;
float absLimitY = 100;
float absLimitZ = 150;
/**
* We want to save the registers we set, so we dont have to read the
* registers when we want to change something.
* --> everytime we change set a register we have to save it
*/
uint8_t registers[MGMLIS3MDL::NR_OF_CTRL_REGISTERS];
uint8_t statusRegister = 0;
bool goToNormalMode = false;
enum class InternalState {
STATE_NONE,
STATE_FIRST_CONTACT,
STATE_SETUP,
STATE_CHECK_REGISTERS,
STATE_NORMAL
};
InternalState internalState = InternalState::STATE_NONE;
CommunicationStep communicationStep = CommunicationStep::DATA;
bool commandExecuted = false;
/*------------------------------------------------------------------------*/
/* Device specific commands and variables */
/*------------------------------------------------------------------------*/
/**
* Sets the read bit for the command
* @param single command to set the read-bit at
* @param boolean to select a continuous read bit, default = false
*/
uint8_t readCommand(uint8_t command, bool continuousCom = false);
/**
* Sets the write bit for the command
* @param single command to set the write-bit at
* @param boolean to select a continuous write bit, default = false
*/
uint8_t writeCommand(uint8_t command, bool continuousCom = false);
/**
* This Method gets the full scale for the measurement range
* e.g.: +- 4 gauss. See p.25 datasheet.
* @return The ReturnValue does not contain the sign of the value
*/
MGMLIS3MDL::Sensitivies getSensitivity(uint8_t ctrlReg2);
/**
* The 16 bit value needs to be multiplied with a sensitivity factor
* which depends on the sensitivity configuration
*
* @param sens Configured sensitivity of the LIS3 device
* @return Multiplication factor to get the sensor value from raw data.
*/
float getSensitivityFactor(MGMLIS3MDL::Sensitivies sens);
/**
* This Command detects the device ID
*/
ReturnValue_t identifyDevice();
virtual void setupMgm();
/*------------------------------------------------------------------------*/
/* Non normal commands */
/*------------------------------------------------------------------------*/
/**
* Enables/Disables the integrated Temperaturesensor
* @param commandData On or Off
* @param length of the commandData: has to be 1
*/
virtual ReturnValue_t enableTemperatureSensor(const uint8_t *commandData,
size_t commandDataLen);
/**
* Sets the accuracy of the measurement of the axis. The noise is changing.
* @param commandData LOW, MEDIUM, HIGH, ULTRA
* @param length of the command, has to be 1
*/
virtual ReturnValue_t setOperatingMode(const uint8_t *commandData,
size_t commandDataLen);
/**
* We always update all registers together, so this method updates
* the rawpacket and rawpacketLen, so we just manipulate the local
* saved register
*
*/
ReturnValue_t prepareCtrlRegisterWrite();
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
PeriodicOperationDivider* debugDivider;
#endif
};
#endif /* MISSION_DEVICES_MGMLIS3MDLHANDLER_H_ */

View File

@ -0,0 +1,376 @@
#include "MgmRM3100Handler.h"
#include "fsfw/datapool/PoolReadGuard.h"
#include "fsfw/globalfunctions/bitutility.h"
#include "fsfw/devicehandlers/DeviceHandlerMessage.h"
#include "fsfw/objectmanager/SystemObjectIF.h"
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
MgmRM3100Handler::MgmRM3100Handler(object_id_t objectId,
object_id_t deviceCommunication, CookieIF* comCookie, uint32_t transitionDelay):
DeviceHandlerBase(objectId, deviceCommunication, comCookie),
primaryDataset(this), transitionDelay(transitionDelay) {
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
debugDivider = new PeriodicOperationDivider(3);
#endif
}
MgmRM3100Handler::~MgmRM3100Handler() {}
void MgmRM3100Handler::doStartUp() {
switch(internalState) {
case(InternalState::NONE): {
internalState = InternalState::CONFIGURE_CMM;
break;
}
case(InternalState::CONFIGURE_CMM): {
internalState = InternalState::READ_CMM;
break;
}
case(InternalState::READ_CMM): {
if(commandExecuted) {
internalState = InternalState::STATE_CONFIGURE_TMRC;
}
break;
}
case(InternalState::STATE_CONFIGURE_TMRC): {
if(commandExecuted) {
internalState = InternalState::STATE_READ_TMRC;
}
break;
}
case(InternalState::STATE_READ_TMRC): {
if(commandExecuted) {
internalState = InternalState::NORMAL;
if(goToNormalModeAtStartup) {
setMode(MODE_NORMAL);
}
else {
setMode(_MODE_TO_ON);
}
}
break;
}
default: {
break;
}
}
}
void MgmRM3100Handler::doShutDown() {
setMode(_MODE_POWER_DOWN);
}
ReturnValue_t MgmRM3100Handler::buildTransitionDeviceCommand(
DeviceCommandId_t *id) {
size_t commandLen = 0;
switch(internalState) {
case(InternalState::NONE):
case(InternalState::NORMAL): {
return NOTHING_TO_SEND;
}
case(InternalState::CONFIGURE_CMM): {
*id = RM3100::CONFIGURE_CMM;
break;
}
case(InternalState::READ_CMM): {
*id = RM3100::READ_CMM;
break;
}
case(InternalState::STATE_CONFIGURE_TMRC): {
commandBuffer[0] = RM3100::TMRC_DEFAULT_VALUE;
commandLen = 1;
*id = RM3100::CONFIGURE_TMRC;
break;
}
case(InternalState::STATE_READ_TMRC): {
*id = RM3100::READ_TMRC;
break;
}
default:
#if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
// Might be a configuration error
sif::warning << "MgmRM3100Handler::buildTransitionDeviceCommand: "
"Unknown internal state" << std::endl;
#else
sif::printWarning("MgmRM3100Handler::buildTransitionDeviceCommand: "
"Unknown internal state\n");
#endif
#endif
return HasReturnvaluesIF::RETURN_OK;
}
return buildCommandFromCommand(*id, commandBuffer, commandLen);
}
ReturnValue_t MgmRM3100Handler::buildCommandFromCommand(DeviceCommandId_t deviceCommand,
const uint8_t *commandData, size_t commandDataLen) {
switch(deviceCommand) {
case(RM3100::CONFIGURE_CMM): {
commandBuffer[0] = RM3100::CMM_REGISTER;
commandBuffer[1] = RM3100::CMM_VALUE;
rawPacket = commandBuffer;
rawPacketLen = 2;
break;
}
case(RM3100::READ_CMM): {
commandBuffer[0] = RM3100::CMM_REGISTER | RM3100::READ_MASK;
commandBuffer[1] = 0;
rawPacket = commandBuffer;
rawPacketLen = 2;
break;
}
case(RM3100::CONFIGURE_TMRC): {
return handleTmrcConfigCommand(deviceCommand, commandData, commandDataLen);
}
case(RM3100::READ_TMRC): {
commandBuffer[0] = RM3100::TMRC_REGISTER | RM3100::READ_MASK;
commandBuffer[1] = 0;
rawPacket = commandBuffer;
rawPacketLen = 2;
break;
}
case(RM3100::CONFIGURE_CYCLE_COUNT): {
return handleCycleCountConfigCommand(deviceCommand, commandData, commandDataLen);
}
case(RM3100::READ_CYCLE_COUNT): {
commandBuffer[0] = RM3100::CYCLE_COUNT_START_REGISTER | RM3100::READ_MASK;
std::memset(commandBuffer + 1, 0, 6);
rawPacket = commandBuffer;
rawPacketLen = 7;
break;
}
case(RM3100::READ_DATA): {
commandBuffer[0] = RM3100::MEASUREMENT_REG_START | RM3100::READ_MASK;
std::memset(commandBuffer + 1, 0, 9);
rawPacketLen = 10;
break;
}
default:
return DeviceHandlerIF::COMMAND_NOT_IMPLEMENTED;
}
return RETURN_OK;
}
ReturnValue_t MgmRM3100Handler::buildNormalDeviceCommand(
DeviceCommandId_t *id) {
*id = RM3100::READ_DATA;
return buildCommandFromCommand(*id, nullptr, 0);
}
ReturnValue_t MgmRM3100Handler::scanForReply(const uint8_t *start,
size_t len, DeviceCommandId_t *foundId,
size_t *foundLen) {
// For SPI, ID will always be the one of the last sent command
*foundId = this->getPendingCommand();
*foundLen = len;
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t MgmRM3100Handler::interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) {
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
switch(id) {
case(RM3100::CONFIGURE_CMM):
case(RM3100::CONFIGURE_CYCLE_COUNT):
case(RM3100::CONFIGURE_TMRC): {
// We can only check whether write was successful with read operation
if(mode == _MODE_START_UP) {
commandExecuted = true;
}
break;
}
case(RM3100::READ_CMM): {
uint8_t cmmValue = packet[1];
// We clear the seventh bit in any case
// because this one is zero sometimes for some reason
bitutil::bitClear(&cmmValue, 6);
if(cmmValue == cmmRegValue and internalState == InternalState::READ_CMM) {
commandExecuted = true;
}
else {
// Attempt reconfiguration
internalState = InternalState::CONFIGURE_CMM;
return DeviceHandlerIF::DEVICE_REPLY_INVALID;
}
break;
}
case(RM3100::READ_TMRC): {
if(packet[1] == tmrcRegValue) {
commandExecuted = true;
// Reading TMRC was commanded. Trigger event to inform ground
if(mode != _MODE_START_UP) {
triggerEvent(tmrcSet, tmrcRegValue, 0);
}
}
else {
// Attempt reconfiguration
internalState = InternalState::STATE_CONFIGURE_TMRC;
return DeviceHandlerIF::DEVICE_REPLY_INVALID;
}
break;
}
case(RM3100::READ_CYCLE_COUNT): {
uint16_t cycleCountX = packet[1] << 8 | packet[2];
uint16_t cycleCountY = packet[3] << 8 | packet[4];
uint16_t cycleCountZ = packet[5] << 8 | packet[6];
if(cycleCountX != cycleCountRegValueX or cycleCountY != cycleCountRegValueY or
cycleCountZ != cycleCountRegValueZ) {
return DeviceHandlerIF::DEVICE_REPLY_INVALID;
}
// Reading TMRC was commanded. Trigger event to inform ground
if(mode != _MODE_START_UP) {
uint32_t eventParam1 = (cycleCountX << 16) | cycleCountY;
triggerEvent(cycleCountersSet, eventParam1, cycleCountZ);
}
break;
}
case(RM3100::READ_DATA): {
result = handleDataReadout(packet);
break;
}
default:
return DeviceHandlerIF::UNKNOWN_DEVICE_REPLY;
}
return result;
}
ReturnValue_t MgmRM3100Handler::handleCycleCountConfigCommand(DeviceCommandId_t deviceCommand,
const uint8_t *commandData, size_t commandDataLen) {
if(commandData == nullptr) {
return DeviceHandlerIF::INVALID_COMMAND_PARAMETER;
}
// Set cycle count
if(commandDataLen == 2) {
handleCycleCommand(true, commandData, commandDataLen);
}
else if(commandDataLen == 6) {
handleCycleCommand(false, commandData, commandDataLen);
}
else {
return DeviceHandlerIF::INVALID_COMMAND_PARAMETER;
}
commandBuffer[0] = RM3100::CYCLE_COUNT_VALUE;
std::memcpy(commandBuffer + 1, &cycleCountRegValueX, 2);
std::memcpy(commandBuffer + 3, &cycleCountRegValueY, 2);
std::memcpy(commandBuffer + 5, &cycleCountRegValueZ, 2);
rawPacketLen = 7;
rawPacket = commandBuffer;
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t MgmRM3100Handler::handleCycleCommand(bool oneCycleValue,
const uint8_t *commandData, size_t commandDataLen) {
RM3100::CycleCountCommand command(oneCycleValue);
ReturnValue_t result = command.deSerialize(&commandData, &commandDataLen,
SerializeIF::Endianness::BIG);
if(result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
// Data sheet p.30 "while noise limits the useful upper range to ~400 cycle counts."
if(command.cycleCountX > 450 ) {
return DeviceHandlerIF::INVALID_COMMAND_PARAMETER;
}
if(not oneCycleValue and (command.cycleCountY > 450 or command.cycleCountZ > 450)) {
return DeviceHandlerIF::INVALID_COMMAND_PARAMETER;
}
cycleCountRegValueX = command.cycleCountX;
cycleCountRegValueY = command.cycleCountY;
cycleCountRegValueZ = command.cycleCountZ;
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t MgmRM3100Handler::handleTmrcConfigCommand(DeviceCommandId_t deviceCommand,
const uint8_t *commandData, size_t commandDataLen) {
if(commandData == nullptr or commandDataLen != 1) {
return DeviceHandlerIF::INVALID_COMMAND_PARAMETER;
}
commandBuffer[0] = RM3100::TMRC_REGISTER;
commandBuffer[1] = commandData[0];
tmrcRegValue = commandData[0];
rawPacketLen = 2;
rawPacket = commandBuffer;
return HasReturnvaluesIF::RETURN_OK;
}
void MgmRM3100Handler::fillCommandAndReplyMap() {
insertInCommandAndReplyMap(RM3100::CONFIGURE_CMM, 3);
insertInCommandAndReplyMap(RM3100::READ_CMM, 3);
insertInCommandAndReplyMap(RM3100::CONFIGURE_TMRC, 3);
insertInCommandAndReplyMap(RM3100::READ_TMRC, 3);
insertInCommandAndReplyMap(RM3100::CONFIGURE_CYCLE_COUNT, 3);
insertInCommandAndReplyMap(RM3100::READ_CYCLE_COUNT, 3);
insertInCommandAndReplyMap(RM3100::READ_DATA, 3, &primaryDataset);
}
void MgmRM3100Handler::modeChanged(void) {
internalState = InternalState::NONE;
}
ReturnValue_t MgmRM3100Handler::initializeLocalDataPool(
localpool::DataPool &localDataPoolMap, LocalDataPoolManager &poolManager) {
localDataPoolMap.emplace(RM3100::FIELD_STRENGTH_X, new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(RM3100::FIELD_STRENGTH_Y, new PoolEntry<float>({0.0}));
localDataPoolMap.emplace(RM3100::FIELD_STRENGTH_Z, new PoolEntry<float>({0.0}));
return HasReturnvaluesIF::RETURN_OK;
}
uint32_t MgmRM3100Handler::getTransitionDelayMs(Mode_t from, Mode_t to) {
return this->transitionDelay;
}
void MgmRM3100Handler::setToGoToNormalMode(bool enable) {
goToNormalModeAtStartup = enable;
}
ReturnValue_t MgmRM3100Handler::handleDataReadout(const uint8_t *packet) {
// Analyze data here. The sensor generates 24 bit signed values so we need to do some bitshift
// trickery here to calculate the raw values first
int32_t fieldStrengthRawX = ((packet[1] << 24) | (packet[2] << 16) | (packet[3] << 8)) >> 8;
int32_t fieldStrengthRawY = ((packet[4] << 24) | (packet[5] << 16) | (packet[6] << 8)) >> 8;
int32_t fieldStrengthRawZ = ((packet[7] << 24) | (packet[8] << 16) | (packet[3] << 8)) >> 8;
// Now scale to physical value in microtesla
float fieldStrengthX = fieldStrengthRawX * scaleFactorX;
float fieldStrengthY = fieldStrengthRawY * scaleFactorX;
float fieldStrengthZ = fieldStrengthRawZ * scaleFactorX;
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
if(debugDivider->checkAndIncrement()) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::info << "MgmRM3100Handler: Magnetic field strength in"
" microtesla:" << std::endl;
sif::info << "X: " << fieldStrengthX << " uT" << std::endl;
sif::info << "Y: " << fieldStrengthY << " uT" << std::endl;
sif::info << "Z: " << fieldStrengthZ << " uT" << std::endl;
#else
sif::printInfo("MgmRM3100Handler: Magnetic field strength in microtesla:\n");
sif::printInfo("X: %f uT\n", fieldStrengthX);
sif::printInfo("Y: %f uT\n", fieldStrengthY);
sif::printInfo("Z: %f uT\n", fieldStrengthZ);
#endif
}
#endif
// TODO: Sanity check on values?
PoolReadGuard readGuard(&primaryDataset);
if(readGuard.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
primaryDataset.fieldStrengthX = fieldStrengthX;
primaryDataset.fieldStrengthY = fieldStrengthY;
primaryDataset.fieldStrengthZ = fieldStrengthZ;
primaryDataset.setValidity(true, true);
}
return RETURN_OK;
}

View File

@ -0,0 +1,111 @@
#ifndef MISSION_DEVICES_MGMRM3100HANDLER_H_
#define MISSION_DEVICES_MGMRM3100HANDLER_H_
#include "fsfw/FSFW.h"
#include "devices/powerSwitcherList.h"
#include "devicedefinitions/MgmRM3100HandlerDefs.h"
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
#include "fsfw/globalfunctions/PeriodicOperationDivider.h"
#endif
/**
* @brief Device Handler for the RM3100 geomagnetic magnetometer sensor
* (https://www.pnicorp.com/rm3100/)
* @details
* Flight manual:
* https://egit.irs.uni-stuttgart.de/redmine/projects/eive-flight-manual/wiki/RM3100_MGM
*/
class MgmRM3100Handler: public DeviceHandlerBase {
public:
static const uint8_t INTERFACE_ID = CLASS_ID::MGM_RM3100;
//! [EXPORT] : [COMMENT] P1: TMRC value which was set, P2: 0
static constexpr Event tmrcSet = event::makeEvent(SUBSYSTEM_ID::MGM_RM3100,
0x00, severity::INFO);
//! [EXPORT] : [COMMENT] Cycle counter set. P1: First two bytes new Cycle Count X
//! P1: Second two bytes new Cycle Count Y
//! P2: New cycle count Z
static constexpr Event cycleCountersSet = event::makeEvent(
SUBSYSTEM_ID::MGM_RM3100, 0x01, severity::INFO);
MgmRM3100Handler(object_id_t objectId, object_id_t deviceCommunication,
CookieIF* comCookie, uint32_t transitionDelay);
virtual ~MgmRM3100Handler();
/**
* Configure device handler to go to normal mode after startup immediately
* @param enable
*/
void setToGoToNormalMode(bool enable);
protected:
/* DeviceHandlerBase overrides */
ReturnValue_t buildTransitionDeviceCommand(
DeviceCommandId_t *id) override;
void doStartUp() override;
void doShutDown() override;
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand,
const uint8_t *commandData, size_t commandDataLen) override;
ReturnValue_t scanForReply(const uint8_t *start, size_t len,
DeviceCommandId_t *foundId, size_t *foundLen) override;
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
void fillCommandAndReplyMap() override;
void modeChanged(void) override;
virtual uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override;
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
LocalDataPoolManager &poolManager) override;
private:
enum class InternalState {
NONE,
CONFIGURE_CMM,
READ_CMM,
// The cycle count states are propably not going to be used because
// the default cycle count will be used.
STATE_CONFIGURE_CYCLE_COUNT,
STATE_READ_CYCLE_COUNT,
STATE_CONFIGURE_TMRC,
STATE_READ_TMRC,
NORMAL
};
InternalState internalState = InternalState::NONE;
bool commandExecuted = false;
RM3100::Rm3100PrimaryDataset primaryDataset;
uint8_t commandBuffer[10];
uint8_t commandBufferLen = 0;
uint8_t cmmRegValue = RM3100::CMM_VALUE;
uint8_t tmrcRegValue = RM3100::TMRC_DEFAULT_VALUE;
uint16_t cycleCountRegValueX = RM3100::CYCLE_COUNT_VALUE;
uint16_t cycleCountRegValueY = RM3100::CYCLE_COUNT_VALUE;
uint16_t cycleCountRegValueZ = RM3100::CYCLE_COUNT_VALUE;
float scaleFactorX = 1.0 / RM3100::DEFAULT_GAIN;
float scaleFactorY = 1.0 / RM3100::DEFAULT_GAIN;
float scaleFactorZ = 1.0 / RM3100::DEFAULT_GAIN;
bool goToNormalModeAtStartup = false;
uint32_t transitionDelay;
ReturnValue_t handleCycleCountConfigCommand(DeviceCommandId_t deviceCommand,
const uint8_t *commandData,size_t commandDataLen);
ReturnValue_t handleCycleCommand(bool oneCycleValue,
const uint8_t *commandData, size_t commandDataLen);
ReturnValue_t handleTmrcConfigCommand(DeviceCommandId_t deviceCommand,
const uint8_t *commandData,size_t commandDataLen);
ReturnValue_t handleDataReadout(const uint8_t* packet);
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
PeriodicOperationDivider* debugDivider;
#endif
};
#endif /* MISSION_DEVICEHANDLING_MGMRM3100HANDLER_H_ */

View File

@ -0,0 +1,178 @@
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_MGMLIS3HANDLERDEFS_H_
#define MISSION_DEVICES_DEVICEDEFINITIONS_MGMLIS3HANDLERDEFS_H_
#include <fsfw/datapoollocal/StaticLocalDataSet.h>
#include <fsfw/datapoollocal/LocalPoolVariable.h>
#include <fsfw/devicehandlers/DeviceHandlerIF.h>
#include <cstdint>
namespace MGMLIS3MDL {
enum Set {
ON, OFF
};
enum OpMode {
LOW, MEDIUM, HIGH, ULTRA
};
enum Sensitivies: uint8_t {
GAUSS_4 = 4,
GAUSS_8 = 8,
GAUSS_12 = 12,
GAUSS_16 = 16
};
/* Actually 15, we just round up a bit */
static constexpr size_t MAX_BUFFER_SIZE = 16;
/* Field data register scaling */
static constexpr uint8_t GAUSS_TO_MICROTESLA_FACTOR = 100;
static constexpr float FIELD_LSB_PER_GAUSS_4_SENS = 1.0 / 6842.0;
static constexpr float FIELD_LSB_PER_GAUSS_8_SENS = 1.0 / 3421.0;
static constexpr float FIELD_LSB_PER_GAUSS_12_SENS = 1.0 / 2281.0;
static constexpr float FIELD_LSB_PER_GAUSS_16_SENS = 1.0 / 1711.0;
static const DeviceCommandId_t READ_CONFIG_AND_DATA = 0x00;
static const DeviceCommandId_t SETUP_MGM = 0x01;
static const DeviceCommandId_t READ_TEMPERATURE = 0x02;
static const DeviceCommandId_t IDENTIFY_DEVICE = 0x03;
static const DeviceCommandId_t TEMP_SENSOR_ENABLE = 0x04;
static const DeviceCommandId_t ACCURACY_OP_MODE_SET = 0x05;
/* Number of all control registers */
static const uint8_t NR_OF_CTRL_REGISTERS = 5;
/* Number of registers in the MGM */
static const uint8_t NR_OF_REGISTERS = 19;
/* Total number of adresses for all registers */
static const uint8_t TOTAL_NR_OF_ADRESSES = 52;
static const uint8_t NR_OF_DATA_AND_CFG_REGISTERS = 14;
static const uint8_t TEMPERATURE_REPLY_LEN = 3;
static const uint8_t SETUP_REPLY_LEN = 6;
/*------------------------------------------------------------------------*/
/* Register adresses */
/*------------------------------------------------------------------------*/
/* Register adress returns identifier of device with default 0b00111101 */
static const uint8_t IDENTIFY_DEVICE_REG_ADDR = 0b00001111;
static const uint8_t DEVICE_ID = 0b00111101; // Identifier for Device
/* Register adress to access register 1 */
static const uint8_t CTRL_REG1 = 0b00100000;
/* Register adress to access register 2 */
static const uint8_t CTRL_REG2 = 0b00100001;
/* Register adress to access register 3 */
static const uint8_t CTRL_REG3 = 0b00100010;
/* Register adress to access register 4 */
static const uint8_t CTRL_REG4 = 0b00100011;
/* Register adress to access register 5 */
static const uint8_t CTRL_REG5 = 0b00100100;
/* Register adress to access status register */
static const uint8_t STATUS_REG_IDX = 8;
static const uint8_t STATUS_REG = 0b00100111;
/* Register adress to access low byte of x-axis */
static const uint8_t X_LOWBYTE_IDX = 9;
static const uint8_t X_LOWBYTE = 0b00101000;
/* Register adress to access high byte of x-axis */
static const uint8_t X_HIGHBYTE_IDX = 10;
static const uint8_t X_HIGHBYTE = 0b00101001;
/* Register adress to access low byte of y-axis */
static const uint8_t Y_LOWBYTE_IDX = 11;
static const uint8_t Y_LOWBYTE = 0b00101010;
/* Register adress to access high byte of y-axis */
static const uint8_t Y_HIGHBYTE_IDX = 12;
static const uint8_t Y_HIGHBYTE = 0b00101011;
/* Register adress to access low byte of z-axis */
static const uint8_t Z_LOWBYTE_IDX = 13;
static const uint8_t Z_LOWBYTE = 0b00101100;
/* Register adress to access high byte of z-axis */
static const uint8_t Z_HIGHBYTE_IDX = 14;
static const uint8_t Z_HIGHBYTE = 0b00101101;
/* Register adress to access low byte of temperature sensor */
static const uint8_t TEMP_LOWBYTE = 0b00101110;
/* Register adress to access high byte of temperature sensor */
static const uint8_t TEMP_HIGHBYTE = 0b00101111;
/*------------------------------------------------------------------------*/
/* Initialize Setup Register set bits */
/*------------------------------------------------------------------------*/
/* General transfer bits */
// Read=1 / Write=0 Bit
static const uint8_t RW_BIT = 7;
// Continous Read/Write Bit, increment adress
static const uint8_t MS_BIT = 6;
/* CTRL_REG1 bits */
static const uint8_t ST = 0; // Self test enable bit, enabled = 1
// Enable rates higher than 80 Hz enabled = 1
static const uint8_t FAST_ODR = 1;
static const uint8_t DO0 = 2; // Output data rate bit 2
static const uint8_t DO1 = 3; // Output data rate bit 3
static const uint8_t DO2 = 4; // Output data rate bit 4
static const uint8_t OM0 = 5; // XY operating mode bit 5
static const uint8_t OM1 = 6; // XY operating mode bit 6
static const uint8_t TEMP_EN = 7; // Temperature sensor enable enabled = 1
static const uint8_t CTRL_REG1_DEFAULT = (1 << TEMP_EN) | (1 << OM1) |
(1 << DO0) | (1 << DO1) | (1 << DO2);
/* CTRL_REG2 bits */
//reset configuration registers and user registers
static const uint8_t SOFT_RST = 2;
static const uint8_t REBOOT = 3; //reboot memory content
static const uint8_t FSO = 5; //full-scale selection bit 5
static const uint8_t FS1 = 6; //full-scale selection bit 6
static const uint8_t CTRL_REG2_DEFAULT = 0;
/* CTRL_REG3 bits */
static const uint8_t MD0 = 0; //Operating mode bit 0
static const uint8_t MD1 = 1; //Operating mode bit 1
//SPI serial interface mode selection enabled = 3-wire-mode
static const uint8_t SIM = 2;
static const uint8_t LP = 5; //low-power mode
static const uint8_t CTRL_REG3_DEFAULT = 0;
/* CTRL_REG4 bits */
//big/little endian data selection enabled = MSb at lower adress
static const uint8_t BLE = 1;
static const uint8_t OMZ0 = 2; //Z operating mode bit 2
static const uint8_t OMZ1 = 3; //Z operating mode bit 3
static const uint8_t CTRL_REG4_DEFAULT = (1 << OMZ1);
/* CTRL_REG5 bits */
static const uint8_t BDU = 6; //Block data update
static const uint8_t FAST_READ = 7; //Fast read enabled = 1
static const uint8_t CTRL_REG5_DEFAULT = 0;
static const uint32_t MGM_DATA_SET_ID = READ_CONFIG_AND_DATA;
enum MgmPoolIds: lp_id_t {
FIELD_STRENGTH_X,
FIELD_STRENGTH_Y,
FIELD_STRENGTH_Z,
TEMPERATURE_CELCIUS
};
class MgmPrimaryDataset: public StaticLocalDataSet<4> {
public:
MgmPrimaryDataset(HasLocalDataPoolIF* hkOwner):
StaticLocalDataSet(hkOwner, MGM_DATA_SET_ID) {}
MgmPrimaryDataset(object_id_t mgmId):
StaticLocalDataSet(sid_t(mgmId, MGM_DATA_SET_ID)) {}
lp_var_t<float> fieldStrengthX = lp_var_t<float>(sid.objectId,
FIELD_STRENGTH_X, this);
lp_var_t<float> fieldStrengthY = lp_var_t<float>(sid.objectId,
FIELD_STRENGTH_Y, this);
lp_var_t<float> fieldStrengthZ = lp_var_t<float>(sid.objectId,
FIELD_STRENGTH_Z, this);
lp_var_t<float> temperature = lp_var_t<float>(sid.objectId,
TEMPERATURE_CELCIUS, this);
};
}
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_MGMLIS3HANDLERDEFS_H_ */

View File

@ -0,0 +1,132 @@
#ifndef MISSION_DEVICES_DEVICEDEFINITIONS_MGMHANDLERRM3100DEFINITIONS_H_
#define MISSION_DEVICES_DEVICEDEFINITIONS_MGMHANDLERRM3100DEFINITIONS_H_
#include <fsfw/datapoollocal/StaticLocalDataSet.h>
#include <fsfw/datapoollocal/LocalPoolVariable.h>
#include <fsfw/devicehandlers/DeviceHandlerIF.h>
#include <fsfw/serialize/SerialLinkedListAdapter.h>
#include <cstdint>
namespace RM3100 {
/* Actually 10, we round up a little bit */
static constexpr size_t MAX_BUFFER_SIZE = 12;
static constexpr uint8_t READ_MASK = 0x80;
/*----------------------------------------------------------------------------*/
/* CMM Register */
/*----------------------------------------------------------------------------*/
static constexpr uint8_t SET_CMM_CMZ = 1 << 6;
static constexpr uint8_t SET_CMM_CMY = 1 << 5;
static constexpr uint8_t SET_CMM_CMX = 1 << 4;
static constexpr uint8_t SET_CMM_DRDM = 1 << 2;
static constexpr uint8_t SET_CMM_START = 1;
static constexpr uint8_t CMM_REGISTER = 0x01;
static constexpr uint8_t CMM_VALUE = SET_CMM_CMZ | SET_CMM_CMY | SET_CMM_CMX |
SET_CMM_DRDM | SET_CMM_START;
/*----------------------------------------------------------------------------*/
/* Cycle count register */
/*----------------------------------------------------------------------------*/
// Default value (200)
static constexpr uint8_t CYCLE_COUNT_VALUE = 0xC8;
static constexpr float DEFAULT_GAIN = static_cast<float>(CYCLE_COUNT_VALUE) /
100 * 38;
static constexpr uint8_t CYCLE_COUNT_START_REGISTER = 0x04;
/*----------------------------------------------------------------------------*/
/* TMRC register */
/*----------------------------------------------------------------------------*/
static constexpr uint8_t TMRC_150HZ_VALUE = 0x94;
static constexpr uint8_t TMRC_75HZ_VALUE = 0x95;
static constexpr uint8_t TMRC_DEFAULT_37HZ_VALUE = 0x96;
static constexpr uint8_t TMRC_REGISTER = 0x0B;
static constexpr uint8_t TMRC_DEFAULT_VALUE = TMRC_DEFAULT_37HZ_VALUE;
static constexpr uint8_t MEASUREMENT_REG_START = 0x24;
static constexpr uint8_t BIST_REGISTER = 0x33;
static constexpr uint8_t DATA_READY_VAL = 0b1000'0000;
static constexpr uint8_t STATUS_REGISTER = 0x34;
static constexpr uint8_t REVID_REGISTER = 0x36;
// Range in Microtesla. 1 T equals 10000 Gauss (for comparison with LIS3 MGM)
static constexpr uint16_t RANGE = 800;
static constexpr DeviceCommandId_t READ_DATA = 0;
static constexpr DeviceCommandId_t CONFIGURE_CMM = 1;
static constexpr DeviceCommandId_t READ_CMM = 2;
static constexpr DeviceCommandId_t CONFIGURE_TMRC = 3;
static constexpr DeviceCommandId_t READ_TMRC = 4;
static constexpr DeviceCommandId_t CONFIGURE_CYCLE_COUNT = 5;
static constexpr DeviceCommandId_t READ_CYCLE_COUNT = 6;
class CycleCountCommand: public SerialLinkedListAdapter<SerializeIF> {
public:
CycleCountCommand(bool oneCycleCount = true): oneCycleCount(oneCycleCount) {
setLinks(oneCycleCount);
}
ReturnValue_t deSerialize(const uint8_t** buffer, size_t* size,
Endianness streamEndianness) override {
ReturnValue_t result = SerialLinkedListAdapter::deSerialize(buffer,
size, streamEndianness);
if(oneCycleCount) {
cycleCountY = cycleCountX;
cycleCountZ = cycleCountX;
}
return result;
}
SerializeElement<uint16_t> cycleCountX;
SerializeElement<uint16_t> cycleCountY;
SerializeElement<uint16_t> cycleCountZ;
private:
void setLinks(bool oneCycleCount) {
setStart(&cycleCountX);
if(not oneCycleCount) {
cycleCountX.setNext(&cycleCountY);
cycleCountY.setNext(&cycleCountZ);
}
}
bool oneCycleCount;
};
static constexpr uint32_t MGM_DATASET_ID = READ_DATA;
enum MgmPoolIds: lp_id_t {
FIELD_STRENGTH_X,
FIELD_STRENGTH_Y,
FIELD_STRENGTH_Z,
};
class Rm3100PrimaryDataset: public StaticLocalDataSet<3> {
public:
Rm3100PrimaryDataset(HasLocalDataPoolIF* hkOwner):
StaticLocalDataSet(hkOwner, MGM_DATASET_ID) {}
Rm3100PrimaryDataset(object_id_t mgmId):
StaticLocalDataSet(sid_t(mgmId, MGM_DATASET_ID)) {}
// Field strengths in micro Tesla.
lp_var_t<float> fieldStrengthX = lp_var_t<float>(sid.objectId,
FIELD_STRENGTH_X, this);
lp_var_t<float> fieldStrengthY = lp_var_t<float>(sid.objectId,
FIELD_STRENGTH_Y, this);
lp_var_t<float> fieldStrengthZ = lp_var_t<float>(sid.objectId,
FIELD_STRENGTH_Z, this);
};
}
#endif /* MISSION_DEVICES_DEVICEDEFINITIONS_MGMHANDLERRM3100DEFINITIONS_H_ */

View File

@ -1,5 +1,10 @@
#include "fsfw/FSFW.h"
#include "fsfw/serviceinterface.h"
#include "fsfw_hal/linux/UnixFileGuard.h"
#include <cerrno>
#include <cstring>
UnixFileGuard::UnixFileGuard(std::string device, int* fileDescriptor, int flags,
std::string diagnosticPrefix):
fileDescriptor(fileDescriptor) {
@ -10,12 +15,11 @@ UnixFileGuard::UnixFileGuard(std::string device, int* fileDescriptor, int flags,
if (*fileDescriptor < 0) {
#if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << diagnosticPrefix <<"Opening device failed with error code " << errno <<
"." << std::endl;
sif::warning << "Error description: " << strerror(errno) << std::endl;
sif::warning << diagnosticPrefix << ": Opening device failed with error code " <<
errno << ": " << strerror(errno) << std::endl;
#else
sif::printError("%sOpening device failed with error code %d.\n", diagnosticPrefix);
sif::printWarning("Error description: %s\n", strerror(errno));
sif::printWarning("%s: Opening device failed with error code %d: %s\n",
diagnosticPrefix, errno, strerror(errno));
#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */
#endif /* FSFW_VERBOSE_LEVEL >= 1 */
openStatus = OPEN_FILE_FAILED;

View File

@ -20,7 +20,7 @@ LinuxLibgpioIF::~LinuxLibgpioIF() {
ReturnValue_t LinuxLibgpioIF::addGpios(GpioCookie* gpioCookie) {
ReturnValue_t result;
if(gpioCookie == nullptr) {
sif::error << "LinuxLibgpioIF::initialize: Invalid cookie" << std::endl;
sif::error << "LinuxLibgpioIF::addGpios: Invalid cookie" << std::endl;
return RETURN_FAILED;
}
@ -45,16 +45,25 @@ ReturnValue_t LinuxLibgpioIF::addGpios(GpioCookie* gpioCookie) {
ReturnValue_t LinuxLibgpioIF::configureGpios(GpioMap& mapToAdd) {
for(auto& gpioConfig: mapToAdd) {
switch(gpioConfig.second->gpioType) {
auto& gpioType = gpioConfig.second->gpioType;
switch(gpioType) {
case(gpio::GpioTypes::NONE): {
return GPIO_INVALID_INSTANCE;
}
case(gpio::GpioTypes::GPIO_REGULAR): {
GpiodRegular* regularGpio = dynamic_cast<GpiodRegular*>(gpioConfig.second);
case(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP): {
auto regularGpio = dynamic_cast<GpiodRegularByChip*>(gpioConfig.second);
if(regularGpio == nullptr) {
return GPIO_INVALID_INSTANCE;
}
configureRegularGpio(gpioConfig.first, regularGpio);
configureGpioByChip(gpioConfig.first, *regularGpio);
break;
}
case(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL):{
auto regularGpio = dynamic_cast<GpiodRegularByLabel*>(gpioConfig.second);
if(regularGpio == nullptr) {
return GPIO_INVALID_INSTANCE;
}
configureGpioByLabel(gpioConfig.first, *regularGpio);
break;
}
case(gpio::GpioTypes::CALLBACK): {
@ -70,41 +79,59 @@ ReturnValue_t LinuxLibgpioIF::configureGpios(GpioMap& mapToAdd) {
return RETURN_OK;
}
ReturnValue_t LinuxLibgpioIF::configureRegularGpio(gpioId_t gpioId, GpiodRegular *regularGpio) {
std::string chipname;
ReturnValue_t LinuxLibgpioIF::configureGpioByLabel(gpioId_t gpioId,
GpiodRegularByLabel &gpioByLabel) {
std::string& label = gpioByLabel.label;
struct gpiod_chip* chip = gpiod_chip_open_by_label(label.c_str());
if (chip == nullptr) {
sif::warning << "LinuxLibgpioIF::configureRegularGpio: Failed to open gpio from gpio "
<< "group with label " << label << ". Gpio ID: " << gpioId << std::endl;
return RETURN_FAILED;
}
std::string failOutput = "label: " + label;
return configureRegularGpio(gpioId, gpioByLabel.gpioType, chip, gpioByLabel, failOutput);
}
ReturnValue_t LinuxLibgpioIF::configureGpioByChip(gpioId_t gpioId,
GpiodRegularByChip &gpioByChip) {
std::string& chipname = gpioByChip.chipname;
struct gpiod_chip* chip = gpiod_chip_open_by_name(chipname.c_str());
if (chip == nullptr) {
sif::warning << "LinuxLibgpioIF::configureRegularGpio: Failed to open chip "
<< chipname << ". Gpio ID: " << gpioId << std::endl;
return RETURN_FAILED;
}
std::string failOutput = "chipname: " + chipname;
return configureRegularGpio(gpioId, gpioByChip.gpioType, chip, gpioByChip, failOutput);
}
ReturnValue_t LinuxLibgpioIF::configureRegularGpio(gpioId_t gpioId, gpio::GpioTypes gpioType,
struct gpiod_chip* chip, GpiodRegularBase& regularGpio, std::string failOutput) {
unsigned int lineNum;
struct gpiod_chip *chip;
gpio::Direction direction;
std::string consumer;
struct gpiod_line *lineHandle;
int result = 0;
chipname = regularGpio->chipname;
chip = gpiod_chip_open_by_name(chipname.c_str());
if (!chip) {
sif::warning << "LinuxLibgpioIF::configureRegularGpio: Failed to open chip "
<< chipname << ". Gpio ID: " << gpioId << std::endl;
return RETURN_FAILED;
}
lineNum = regularGpio->lineNum;
lineNum = regularGpio.lineNum;
lineHandle = gpiod_chip_get_line(chip, lineNum);
if (!lineHandle) {
sif::debug << "LinuxLibgpioIF::configureRegularGpio: Failed to open line " << std::endl;
sif::debug << "GPIO ID: " << gpioId << ", line number: " << lineNum <<
", chipname: " << chipname << std::endl;
sif::debug << "Check if linux GPIO configuration has changed. " << std::endl;
sif::warning << "LinuxLibgpioIF::configureRegularGpio: Failed to open line " << std::endl;
sif::warning << "GPIO ID: " << gpioId << ", line number: " << lineNum <<
", " << failOutput << std::endl;
sif::warning << "Check if Linux GPIO configuration has changed. " << std::endl;
gpiod_chip_close(chip);
return RETURN_FAILED;
}
direction = regularGpio->direction;
consumer = regularGpio->consumer;
direction = regularGpio.direction;
consumer = regularGpio.consumer;
/* Configure direction and add a description to the GPIO */
switch (direction) {
case(gpio::OUT): {
result = gpiod_line_request_output(lineHandle, consumer.c_str(),
regularGpio->initValue);
regularGpio.initValue);
if (result < 0) {
sif::error << "LinuxLibgpioIF::configureRegularGpio: Failed to request line " << lineNum <<
" from GPIO instance with ID: " << gpioId << std::endl;
@ -134,7 +161,7 @@ ReturnValue_t LinuxLibgpioIF::configureRegularGpio(gpioId_t gpioId, GpiodRegular
* Write line handle to GPIO configuration instance so it can later be used to set or
* read states of GPIOs.
*/
regularGpio->lineHandle = lineHandle;
regularGpio.lineHandle = lineHandle;
return RETURN_OK;
}
@ -145,8 +172,14 @@ ReturnValue_t LinuxLibgpioIF::pullHigh(gpioId_t gpioId) {
return UNKNOWN_GPIO_ID;
}
if(gpioMapIter->second->gpioType == gpio::GpioTypes::GPIO_REGULAR) {
return driveGpio(gpioId, dynamic_cast<GpiodRegular*>(gpioMapIter->second), 1);
auto gpioType = gpioMapIter->second->gpioType;
if(gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_CHIP or
gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LABEL) {
auto regularGpio = dynamic_cast<GpiodRegularBase*>(gpioMapIter->second);
if(regularGpio == nullptr) {
return GPIO_TYPE_FAILURE;
}
return driveGpio(gpioId, *regularGpio, gpio::HIGH);
}
else {
auto gpioCallback = dynamic_cast<GpioCallback*>(gpioMapIter->second);
@ -167,8 +200,14 @@ ReturnValue_t LinuxLibgpioIF::pullLow(gpioId_t gpioId) {
return UNKNOWN_GPIO_ID;
}
if(gpioMapIter->second->gpioType == gpio::GpioTypes::GPIO_REGULAR) {
return driveGpio(gpioId, dynamic_cast<GpiodRegular*>(gpioMapIter->second), 0);
auto& gpioType = gpioMapIter->second->gpioType;
if(gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_CHIP or
gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LABEL) {
auto regularGpio = dynamic_cast<GpiodRegularBase*>(gpioMapIter->second);
if(regularGpio == nullptr) {
return GPIO_TYPE_FAILURE;
}
return driveGpio(gpioId, *regularGpio, gpio::LOW);
}
else {
auto gpioCallback = dynamic_cast<GpioCallback*>(gpioMapIter->second);
@ -183,12 +222,8 @@ ReturnValue_t LinuxLibgpioIF::pullLow(gpioId_t gpioId) {
}
ReturnValue_t LinuxLibgpioIF::driveGpio(gpioId_t gpioId,
GpiodRegular* regularGpio, unsigned int logicLevel) {
if(regularGpio == nullptr) {
return GPIO_TYPE_FAILURE;
}
int result = gpiod_line_set_value(regularGpio->lineHandle, logicLevel);
GpiodRegularBase& regularGpio, gpio::Levels logicLevel) {
int result = gpiod_line_set_value(regularGpio.lineHandle, logicLevel);
if (result < 0) {
sif::warning << "LinuxLibgpioIF::driveGpio: Failed to pull GPIO with ID " << gpioId <<
" to logic level " << logicLevel << std::endl;
@ -204,9 +239,10 @@ ReturnValue_t LinuxLibgpioIF::readGpio(gpioId_t gpioId, int* gpioState) {
sif::warning << "LinuxLibgpioIF::readGpio: Unknown GPIOD ID " << gpioId << std::endl;
return UNKNOWN_GPIO_ID;
}
if(gpioMapIter->second->gpioType == gpio::GpioTypes::GPIO_REGULAR) {
GpiodRegular* regularGpio = dynamic_cast<GpiodRegular*>(gpioMapIter->second);
auto gpioType = gpioMapIter->second->gpioType;
if(gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_CHIP or
gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LABEL) {
auto regularGpio = dynamic_cast<GpiodRegularBase*>(gpioMapIter->second);
if(regularGpio == nullptr) {
return GPIO_TYPE_FAILURE;
}
@ -225,13 +261,14 @@ ReturnValue_t LinuxLibgpioIF::checkForConflicts(GpioMap& mapToAdd){
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
for(auto& gpioConfig: mapToAdd) {
switch(gpioConfig.second->gpioType) {
case(gpio::GpioTypes::GPIO_REGULAR): {
auto regularGpio = dynamic_cast<GpiodRegular*>(gpioConfig.second);
case(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP):
case(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL): {
auto regularGpio = dynamic_cast<GpiodRegularBase*>(gpioConfig.second);
if(regularGpio == nullptr) {
return GPIO_TYPE_FAILURE;
}
/* Check for conflicts and remove duplicates if necessary */
result = checkForConflictsRegularGpio(gpioConfig.first, regularGpio, mapToAdd);
result = checkForConflictsRegularGpio(gpioConfig.first, *regularGpio, mapToAdd);
if(result != HasReturnvaluesIF::RETURN_OK) {
status = result;
}
@ -259,17 +296,19 @@ ReturnValue_t LinuxLibgpioIF::checkForConflicts(GpioMap& mapToAdd){
ReturnValue_t LinuxLibgpioIF::checkForConflictsRegularGpio(gpioId_t gpioIdToCheck,
GpiodRegular* gpioToCheck, GpioMap& mapToAdd) {
GpiodRegularBase& gpioToCheck, GpioMap& mapToAdd) {
/* Cross check with private map */
gpioMapIter = gpioMap.find(gpioIdToCheck);
if(gpioMapIter != gpioMap.end()) {
if(gpioMapIter->second->gpioType != gpio::GpioTypes::GPIO_REGULAR) {
auto& gpioType = gpioMapIter->second->gpioType;
if(gpioType != gpio::GpioTypes::GPIO_REGULAR_BY_CHIP and
gpioType != gpio::GpioTypes::GPIO_REGULAR_BY_LABEL) {
sif::warning << "LinuxLibgpioIF::checkForConflicts: ID already exists for different "
"GPIO type" << gpioIdToCheck << ". Removing duplicate." << std::endl;
mapToAdd.erase(gpioIdToCheck);
return HasReturnvaluesIF::RETURN_OK;
}
auto ownRegularGpio = dynamic_cast<GpiodRegular*>(gpioMapIter->second);
auto ownRegularGpio = dynamic_cast<GpiodRegularBase*>(gpioMapIter->second);
if(ownRegularGpio == nullptr) {
return GPIO_TYPE_FAILURE;
}

View File

@ -6,6 +6,7 @@
#include <fsfw/objectmanager/SystemObject.h>
class GpioCookie;
class GpiodRegularIF;
/**
* @brief This class implements the GpioIF for a linux based system. The
@ -47,9 +48,13 @@ private:
* @param gpioId The GPIO ID of the GPIO to drive.
* @param logiclevel The logic level to set. O or 1.
*/
ReturnValue_t driveGpio(gpioId_t gpioId, GpiodRegular* regularGpio, unsigned int logiclevel);
ReturnValue_t driveGpio(gpioId_t gpioId, GpiodRegularBase& regularGpio,
gpio::Levels logicLevel);
ReturnValue_t configureRegularGpio(gpioId_t gpioId, GpiodRegular* regularGpio);
ReturnValue_t configureGpioByLabel(gpioId_t gpioId, GpiodRegularByLabel& gpioByLabel);
ReturnValue_t configureGpioByChip(gpioId_t gpioId, GpiodRegularByChip& gpioByChip);
ReturnValue_t configureRegularGpio(gpioId_t gpioId, gpio::GpioTypes gpioType,
struct gpiod_chip* chip, GpiodRegularBase& regularGpio, std::string failOutput);
/**
* @brief This function checks if GPIOs are already registered and whether
@ -62,7 +67,7 @@ private:
*/
ReturnValue_t checkForConflicts(GpioMap& mapToAdd);
ReturnValue_t checkForConflictsRegularGpio(gpioId_t gpiodId, GpiodRegular* regularGpio,
ReturnValue_t checkForConflictsRegularGpio(gpioId_t gpiodId, GpiodRegularBase& regularGpio,
GpioMap& mapToAdd);
ReturnValue_t checkForConflictsCallbackGpio(gpioId_t gpiodId, GpioCallback* regularGpio,
GpioMap& mapToAdd);

View File

@ -12,7 +12,7 @@ ReturnValue_t gpio::createRpiGpioConfig(GpioCookie* cookie, gpioId_t gpioId, int
return HasReturnvaluesIF::RETURN_FAILED;
}
GpiodRegular* config = new GpiodRegular();
auto config = new GpiodRegularByChip();
/* Default chipname for Raspberry Pi. There is still gpiochip1 for expansion, but most users
will not need this */
config->chipname = "gpiochip0";

View File

@ -15,11 +15,6 @@
#include <cerrno>
#include <cstring>
/* Can be used for low-level debugging of the SPI bus */
#ifndef FSFW_HAL_LINUX_SPI_WIRETAPPING
#define FSFW_HAL_LINUX_SPI_WIRETAPPING 0
#endif
SpiComIF::SpiComIF(object_id_t objectId, GpioIF* gpioComIF):
SystemObject(objectId), gpioComIF(gpioComIF) {
if(gpioComIF == nullptr) {
@ -90,7 +85,7 @@ ReturnValue_t SpiComIF::initializeInterface(CookieIF *cookie) {
int fileDescriptor = 0;
UnixFileGuard fileHelper(spiCookie->getSpiDevice(), &fileDescriptor, O_RDWR,
"SpiComIF::initializeInterface: ");
"SpiComIF::initializeInterface");
if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) {
return fileHelper.getOpenResult();
}
@ -146,8 +141,8 @@ ReturnValue_t SpiComIF::sendMessage(CookieIF *cookie, const uint8_t *sendData, s
if(sendLen > spiCookie->getMaxBufferSize()) {
#if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "SpiComIF::sendMessage: Too much data sent, send length" << sendLen <<
"larger than maximum buffer length" << spiCookie->getMaxBufferSize() << std::endl;
sif::warning << "SpiComIF::sendMessage: Too much data sent, send length " << sendLen <<
"larger than maximum buffer length " << spiCookie->getMaxBufferSize() << std::endl;
#else
sif::printWarning("SpiComIF::sendMessage: Too much data sent, send length %lu larger "
"than maximum buffer length %lu!\n", static_cast<unsigned long>(sendLen),
@ -184,7 +179,7 @@ ReturnValue_t SpiComIF::performRegularSendOperation(SpiCookie *spiCookie, const
/* Prepare transfer */
int fileDescriptor = 0;
std::string device = spiCookie->getSpiDevice();
UnixFileGuard fileHelper(device, &fileDescriptor, O_RDWR, "SpiComIF::sendMessage: ");
UnixFileGuard fileHelper(device, &fileDescriptor, O_RDWR, "SpiComIF::sendMessage");
if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) {
return OPENING_FILE_FAILED;
}
@ -193,7 +188,7 @@ ReturnValue_t SpiComIF::performRegularSendOperation(SpiCookie *spiCookie, const
spiCookie->getSpiParameters(spiMode, spiSpeed, nullptr);
setSpiSpeedAndMode(fileDescriptor, spiMode, spiSpeed);
spiCookie->assignWriteBuffer(sendData);
spiCookie->assignTransferSize(sendLen);
spiCookie->setTransferSize(sendLen);
bool fullDuplex = spiCookie->isFullDuplex();
gpioId_t gpioId = spiCookie->getChipSelectPin();
@ -202,12 +197,26 @@ ReturnValue_t SpiComIF::performRegularSendOperation(SpiCookie *spiCookie, const
if(gpioId != gpio::NO_GPIO) {
result = spiMutex->lockMutex(timeoutType, timeoutMs);
if (result != RETURN_OK) {
#if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::error << "SpiComIF::sendMessage: Failed to lock mutex" << std::endl;
#else
sif::printError("SpiComIF::sendMessage: Failed to lock mutex\n");
#endif
#endif
return result;
}
ReturnValue_t result = gpioComIF->pullLow(gpioId);
if(result != HasReturnvaluesIF::RETURN_OK) {
#if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "SpiComIF::sendMessage: Pulling low CS pin failed" << std::endl;
#else
sif::printWarning("SpiComIF::sendMessage: Pulling low CS pin failed");
#endif
#endif
return result;
}
gpioComIF->pullLow(gpioId);
}
/* Execute transfer */
@ -218,7 +227,7 @@ ReturnValue_t SpiComIF::performRegularSendOperation(SpiCookie *spiCookie, const
utility::handleIoctlError("SpiComIF::sendMessage: ioctl error.");
result = FULL_DUPLEX_TRANSFER_FAILED;
}
#if FSFW_HAL_LINUX_SPI_WIRETAPPING == 1
#if FSFW_HAL_SPI_WIRETAPPING == 1
performSpiWiretapping(spiCookie);
#endif /* FSFW_LINUX_SPI_WIRETAPPING == 1 */
}
@ -273,7 +282,7 @@ ReturnValue_t SpiComIF::performHalfDuplexReception(SpiCookie* spiCookie) {
std::string device = spiCookie->getSpiDevice();
int fileDescriptor = 0;
UnixFileGuard fileHelper(device, &fileDescriptor, O_RDWR,
"SpiComIF::requestReceiveMessage: ");
"SpiComIF::requestReceiveMessage");
if(fileHelper.getOpenResult() != HasReturnvaluesIF::RETURN_OK) {
return OPENING_FILE_FAILED;
}
@ -335,6 +344,7 @@ ReturnValue_t SpiComIF::readReceivedMessage(CookieIF *cookie, uint8_t **buffer,
*buffer = rxBuf;
*size = spiCookie->getCurrentTransferSize();
spiCookie->setTransferSize(0);
return HasReturnvaluesIF::RETURN_OK;
}
@ -388,11 +398,11 @@ GpioIF* SpiComIF::getGpioInterface() {
void SpiComIF::setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed) {
int retval = ioctl(spiFd, SPI_IOC_WR_MODE, reinterpret_cast<uint8_t*>(&mode));
if(retval != 0) {
utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI mode failed!");
utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Setting SPI mode failed");
}
retval = ioctl(spiFd, SPI_IOC_WR_MAX_SPEED_HZ, &speed);
if(retval != 0) {
utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI speed failed!");
utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Setting SPI speed failed");
}
}

View File

@ -1,6 +1,7 @@
#ifndef LINUX_SPI_SPICOMIF_H_
#define LINUX_SPI_SPICOMIF_H_
#include "fsfw/FSFW.h"
#include "spiDefinitions.h"
#include "returnvalues/classIds.h"
#include "fsfw_hal/common/gpio/GpioIF.h"

View File

@ -121,7 +121,7 @@ bool SpiCookie::isFullDuplex() const {
return not this->halfDuplex;
}
void SpiCookie::assignTransferSize(size_t transferSize) {
void SpiCookie::setTransferSize(size_t transferSize) {
spiTransferStruct.len = transferSize;
}

View File

@ -103,10 +103,10 @@ public:
void assignReadBuffer(uint8_t* rx);
void assignWriteBuffer(const uint8_t* tx);
/**
* Assign size for the next transfer.
* Set size for the next transfer. Set to 0 for no transfer
* @param transferSize
*/
void assignTransferSize(size_t transferSize);
void setTransferSize(size_t transferSize);
size_t getCurrentTransferSize() const;
struct UncommonParameters {
@ -158,8 +158,6 @@ private:
std::string spiDev, const size_t maxSize, spi::SpiModes spiMode, uint32_t spiSpeed,
spi::send_callback_function_t callback, void* args);
size_t currentTransferSize = 0;
address_t spiAddress;
gpioId_t chipSelectPin;
std::string spiDevice;

View File

@ -1,6 +1,7 @@
#include "fsfw_hal/linux/uart/UartComIF.h"
#include "UartComIF.h"
#include "OBSWConfig.h"
#include "fsfw_hal/linux/utility.h"
#include "fsfw/serviceinterface/ServiceInterface.h"
#include <cstring>
@ -60,7 +61,13 @@ int UartComIF::configureUartPort(UartCookie* uartCookie) {
struct termios options = {};
std::string deviceFile = uartCookie->getDeviceFile();
int fd = open(deviceFile.c_str(), O_RDWR);
int flags = O_RDWR;
if(uartCookie->getUartMode() == UartModes::CANONICAL) {
// In non-canonical mode, don't specify O_NONBLOCK because these properties will be
// controlled by the VTIME and VMIN parameters and O_NONBLOCK would override this
flags |= O_NONBLOCK;
}
int fd = open(deviceFile.c_str(), flags);
if (fd < 0) {
sif::warning << "UartComIF::configureUartPort: Failed to open uart " << deviceFile <<
@ -259,23 +266,22 @@ void UartComIF::configureBaudrate(struct termios* options, UartCookie* uartCooki
ReturnValue_t UartComIF::sendMessage(CookieIF *cookie,
const uint8_t *sendData, size_t sendLen) {
int fd = 0;
std::string deviceFile;
UartDeviceMapIter uartDeviceMapIter;
if(sendData == nullptr) {
sif::debug << "UartComIF::sendMessage: Send Data is nullptr" << std::endl;
return RETURN_FAILED;
}
if(sendLen == 0) {
return RETURN_OK;
}
if(sendData == nullptr) {
sif::warning << "UartComIF::sendMessage: Send data is nullptr" << std::endl;
return RETURN_FAILED;
}
UartCookie* uartCookie = dynamic_cast<UartCookie*>(cookie);
if(uartCookie == nullptr) {
sif::debug << "UartComIF::sendMessasge: Invalid UART Cookie!" << std::endl;
sif::warning << "UartComIF::sendMessasge: Invalid UART Cookie!" << std::endl;
return NULLPOINTER;
}
@ -347,12 +353,13 @@ ReturnValue_t UartComIF::handleCanonicalRead(UartCookie& uartCookie, UartDeviceM
size_t maxReplySize = uartCookie.getMaxReplyLen();
int fd = iter->second.fileDescriptor;
auto bufferPtr = iter->second.replyBuffer.data();
iter->second.replyLen = 0;
do {
size_t allowedReadSize = 0;
if(currentBytesRead >= maxReplySize) {
// Overflow risk. Emit warning, trigger event and break. If this happens,
// the reception buffer is not large enough or data is not polled often enough.
#if OBSW_VERBOSE_LEVEL >= 1
#if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "UartComIF::requestReceiveMessage: Next read would cause overflow!"
<< std::endl;
@ -370,7 +377,20 @@ ReturnValue_t UartComIF::handleCanonicalRead(UartCookie& uartCookie, UartDeviceM
bytesRead = read(fd, bufferPtr, allowedReadSize);
if (bytesRead < 0) {
return RETURN_FAILED;
// EAGAIN: No data available in non-blocking mode
if(errno != EAGAIN) {
#if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "UartComIF::handleCanonicalRead: read failed with code" <<
errno << ": " << strerror(errno) << std::endl;
#else
sif::printWarning("UartComIF::handleCanonicalRead: read failed with code %d: %s\n",
errno, strerror(errno));
#endif
#endif
return RETURN_FAILED;
}
}
else if(bytesRead > 0) {
iter->second.replyLen += bytesRead;

View File

@ -4,8 +4,8 @@
UartCookie::UartCookie(object_id_t handlerId, std::string deviceFile, UartModes uartMode,
uint32_t baudrate, size_t maxReplyLen):
handlerId(handlerId), deviceFile(deviceFile), uartMode(uartMode), baudrate(baudrate),
maxReplyLen(maxReplyLen) {
handlerId(handlerId), deviceFile(deviceFile), uartMode(uartMode),
baudrate(baudrate), maxReplyLen(maxReplyLen) {
}
UartCookie::~UartCookie() {}

View File

@ -10,7 +10,7 @@
*/
namespace addresses {
/* Logical addresses have uint32_t datatype */
enum logicalAddresses: address_t {
enum LogAddr: address_t {
};
}

View File

@ -16,8 +16,25 @@
#cmakedefine FSFW_ADD_MONITORING
#cmakedefine FSFW_ADD_SGP4_PROPAGATOR
#ifndef FSFW_TCP_RECV_WIRETAPPING_ENABLED
#define FSFW_TCP_RECV_WIRETAPPING_ENABLED 0
#endif
// Can be used for low-level debugging of the SPI bus
#ifndef FSFW_HAL_SPI_WIRETAPPING
#define FSFW_HAL_SPI_WIRETAPPING 0
#endif
#ifndef FSFW_HAL_L3GD20_GYRO_DEBUG
#define FSFW_HAL_L3GD20_GYRO_DEBUG 0
#define FSFW_HAL_L3GD20_GYRO_DEBUG 0
#endif /* FSFW_HAL_L3GD20_GYRO_DEBUG */
#ifndef FSFW_HAL_RM3100_MGM_DEBUG
#define FSFW_HAL_RM3100_MGM_DEBUG 0
#endif /* FSFW_HAL_RM3100_MGM_DEBUG */
#ifndef FSFW_HAL_LIS3MDL_MGM_DEBUG
#define FSFW_HAL_LIS3MDL_MGM_DEBUG 0
#endif /* FSFW_HAL_LIS3MDL_MGM_DEBUG */
#endif /* FSFW_FSFW_H_ */

View File

@ -4,7 +4,7 @@
const char* const FSFW_VERSION_NAME = "ASTP";
#define FSFW_VERSION 1
#define FSFW_SUBVERSION 3
#define FSFW_SUBVERSION 2
#define FSFW_REVISION 0
#endif /* FSFW_VERSION_H_ */

View File

@ -32,6 +32,17 @@ ReturnValue_t ActionHelper::initialize(MessageQueueIF* queueToUse_) {
setQueueToUse(queueToUse_);
}
if(queueToUse == nullptr) {
#if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "ActionHelper::initialize: No queue set" << std::endl;
#else
sif::printWarning("ActionHelper::initialize: No queue set\n");
#endif
#endif /* FSFW_VERBOSE_LEVEL >= 1 */
return HasReturnvaluesIF::RETURN_FAILED;
}
return HasReturnvaluesIF::RETURN_OK;
}

View File

@ -8,11 +8,10 @@
#include "fsfw/datapoollocal/LocalDataPoolManager.h"
/**
* @brief Extendes the basic ControllerBase with the common components
* HasActionsIF for commandability and HasLocalDataPoolIF to keep
* a pool of local data pool variables.
* @brief Extends the basic ControllerBase with commonly used components
* @details
* Default implementations required for the interfaces will be empty and have
* HasActionsIF for commandability and HasLocalDataPoolIF to keep a pool of local data pool
* variables. Default implementations required for the interfaces will be empty and have
* to be implemented by child class.
*/
class ExtendedControllerBase: public ControllerBase,

View File

@ -7,7 +7,7 @@
/**
* @brief Base class to implement reconfiguration and failure handling for
* redundant devices by monitoring their modes health states.
* redundant devices by monitoring their modes and health states.
* @details
* Documentation: Dissertation Baetz p.156, 157.
*

View File

@ -85,9 +85,10 @@ public:
* Called by DHB in the GET_WRITE doGetWrite().
* Get send confirmation that the data in sendMessage() was sent successfully.
* @param cookie
* @return - @c RETURN_OK if data was sent successfull
* - Everything else triggers falure event with
* returnvalue as parameter 1
* @return
* - @c RETURN_OK if data was sent successfully but a reply is expected
* - NO_REPLY_EXPECTED if data was sent successfully and no reply is expected
* - Everything else to indicate failure
*/
virtual ReturnValue_t getSendSuccess(CookieIF *cookie) = 0;

View File

@ -461,7 +461,7 @@ size_t DeviceHandlerBase::getNextReplyLength(DeviceCommandId_t commandId){
return iter->second.replyLen;
}else{
return 0;
}
}
}
ReturnValue_t DeviceHandlerBase::updateReplyMapEntry(DeviceCommandId_t deviceReply,
@ -469,7 +469,7 @@ ReturnValue_t DeviceHandlerBase::updateReplyMapEntry(DeviceCommandId_t deviceRep
auto replyIter = deviceReplyMap.find(deviceReply);
if (replyIter == deviceReplyMap.end()) {
triggerEvent(INVALID_DEVICE_COMMAND, deviceReply);
return RETURN_FAILED;
return COMMAND_NOT_SUPPORTED;
} else {
DeviceReplyInfo *info = &(replyIter->second);
if (maxDelayCycles != 0) {
@ -481,6 +481,25 @@ ReturnValue_t DeviceHandlerBase::updateReplyMapEntry(DeviceCommandId_t deviceRep
}
}
ReturnValue_t DeviceHandlerBase::updatePeriodicReply(bool enable, DeviceCommandId_t deviceReply) {
auto replyIter = deviceReplyMap.find(deviceReply);
if (replyIter == deviceReplyMap.end()) {
triggerEvent(INVALID_DEVICE_COMMAND, deviceReply);
return COMMAND_NOT_SUPPORTED;
} else {
DeviceReplyInfo *info = &(replyIter->second);
if(not info->periodic) {
return COMMAND_NOT_SUPPORTED;
}
if(enable) {
info->delayCycles = info->maxDelayCycles;
}
else {
info->delayCycles = 0;
}
}
return HasReturnvaluesIF::RETURN_OK;
}
ReturnValue_t DeviceHandlerBase::setReplyDataset(DeviceCommandId_t replyId,
LocalPoolDataSetBase *dataSet) {
@ -593,15 +612,15 @@ void DeviceHandlerBase::replyToReply(const DeviceCommandId_t command, DeviceRepl
}
DeviceCommandInfo* info = &replyInfo.command->second;
if (info == nullptr){
printWarningOrError(sif::OutputTypes::OUT_ERROR,
"replyToReply", HasReturnvaluesIF::RETURN_FAILED,
"Command pointer not found");
return;
printWarningOrError(sif::OutputTypes::OUT_ERROR,
"replyToReply", HasReturnvaluesIF::RETURN_FAILED,
"Command pointer not found");
return;
}
if (info->expectedReplies > 0){
// Check before to avoid underflow
info->expectedReplies--;
// Check before to avoid underflow
info->expectedReplies--;
}
// Check if more replies are expected. If so, do nothing.
if (info->expectedReplies == 0) {
@ -1336,10 +1355,20 @@ void DeviceHandlerBase::buildInternalCommand(void) {
DeviceCommandMap::iterator iter = deviceCommandMap.find(
deviceCommandId);
if (iter == deviceCommandMap.end()) {
#if FSFW_VERBOSE_LEVEL >= 1
char output[36];
sprintf(output, "Command 0x%08x unknown",
static_cast<unsigned int>(deviceCommandId));
// so we can track misconfigurations
printWarningOrError(sif::OutputTypes::OUT_WARNING,
"buildInternalCommand",
COMMAND_NOT_SUPPORTED,
output);
#endif
result = COMMAND_NOT_SUPPORTED;
}
else if (iter->second.isExecuting) {
#if FSFW_DISABLE_PRINTOUT == 0
#if FSFW_VERBOSE_LEVEL >= 1
char output[36];
sprintf(output, "Command 0x%08x is executing",
static_cast<unsigned int>(deviceCommandId));
@ -1550,7 +1579,7 @@ LocalDataPoolManager* DeviceHandlerBase::getHkManagerHandle() {
return &poolManager;
}
MessageQueueId_t DeviceHandlerBase::getCommanderId(DeviceCommandId_t replyId) const {
MessageQueueId_t DeviceHandlerBase::getCommanderQueueId(DeviceCommandId_t replyId) const {
auto commandIter = deviceCommandMap.find(replyId);
if(commandIter == deviceCommandMap.end()) {
return MessageQueueIF::NO_QUEUE;

View File

@ -6,22 +6,22 @@
#include "DeviceHandlerFailureIsolation.h"
#include "DeviceHandlerThermalSet.h"
#include "../serviceinterface/ServiceInterface.h"
#include "../serviceinterface/serviceInterfaceDefintions.h"
#include "../objectmanager/SystemObject.h"
#include "../tasks/ExecutableObjectIF.h"
#include "../returnvalues/HasReturnvaluesIF.h"
#include "../action/HasActionsIF.h"
#include "../datapool/PoolVariableIF.h"
#include "../modes/HasModesIF.h"
#include "../power/PowerSwitchIF.h"
#include "../ipc/MessageQueueIF.h"
#include "../tasks/PeriodicTaskIF.h"
#include "../action/ActionHelper.h"
#include "../health/HealthHelper.h"
#include "../parameters/ParameterHelper.h"
#include "../datapoollocal/HasLocalDataPoolIF.h"
#include "../datapoollocal/LocalDataPoolManager.h"
#include "fsfw/serviceinterface/ServiceInterface.h"
#include "fsfw/serviceinterface/serviceInterfaceDefintions.h"
#include "fsfw/objectmanager/SystemObject.h"
#include "fsfw/tasks/ExecutableObjectIF.h"
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
#include "fsfw/action/HasActionsIF.h"
#include "fsfw/datapool/PoolVariableIF.h"
#include "fsfw/modes/HasModesIF.h"
#include "fsfw/power/PowerSwitchIF.h"
#include "fsfw/ipc/MessageQueueIF.h"
#include "fsfw/tasks/PeriodicTaskIF.h"
#include "fsfw/action/ActionHelper.h"
#include "fsfw/health/HealthHelper.h"
#include "fsfw/parameters/ParameterHelper.h"
#include "fsfw/datapoollocal/HasLocalDataPoolIF.h"
#include "fsfw/datapoollocal/LocalDataPoolManager.h"
#include <map>
@ -78,15 +78,16 @@ class StorageManagerIF;
*
* @ingroup devices
*/
class DeviceHandlerBase: public DeviceHandlerIF,
public HasReturnvaluesIF,
public ExecutableObjectIF,
public SystemObject,
public HasModesIF,
public HasHealthIF,
public HasActionsIF,
public ReceivesParameterMessagesIF,
public HasLocalDataPoolIF {
class DeviceHandlerBase:
public DeviceHandlerIF,
public HasReturnvaluesIF,
public ExecutableObjectIF,
public SystemObject,
public HasModesIF,
public HasHealthIF,
public HasActionsIF,
public ReceivesParameterMessagesIF,
public HasLocalDataPoolIF {
friend void (Factory::setStaticFrameworkObjectIds)();
public:
/**
@ -334,8 +335,7 @@ protected:
* - @c RETURN_OK to send command after #rawPacket and #rawPacketLen
* have been set.
* - @c HasActionsIF::EXECUTION_COMPLETE to generate a finish reply immediately. This can
* be used if no reply is expected. Otherwise, the developer can call #actionHelper.finish
* to finish the command handling.
* be used if no reply is expected
* - Anything else triggers an event with the return code as a parameter as well as a
* step reply failed with the return code
*/
@ -399,7 +399,7 @@ protected:
*/
virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id,
const uint8_t *packet) = 0;
MessageQueueId_t getCommanderId(DeviceCommandId_t replyId) const;
MessageQueueId_t getCommanderQueueId(DeviceCommandId_t replyId) const;
/**
* Helper function to get pending command. This is useful for devices
* like SPI sensors to identify the last sent command.
@ -449,7 +449,9 @@ protected:
* @param replyLen Will be supplied to the requestReceiveMessage call of
* the communication interface.
* @param periodic Indicates if the command is periodic (i.e. it is sent
* by the device repeatedly without request) or not. Default is aperiodic (0)
* by the device repeatedly without request) or not. Default is aperiodic (0).
* Please note that periodic replies are disabled by default. You can enable them with
* #updatePeriodicReply
* @return - @c RETURN_OK when the command was successfully inserted,
* - @c RETURN_FAILED else.
*/
@ -464,7 +466,9 @@ protected:
* @param maxDelayCycles The maximum number of delay cycles the reply waits
* until it times out.
* @param periodic Indicates if the command is periodic (i.e. it is sent
* by the device repeatedly without request) or not. Default is aperiodic (0)
* by the device repeatedly without request) or not. Default is aperiodic (0).
* Please note that periodic replies are disabled by default. You can enable them with
* #updatePeriodicReply
* @return - @c RETURN_OK when the command was successfully inserted,
* - @c RETURN_FAILED else.
*/
@ -480,6 +484,14 @@ protected:
*/
ReturnValue_t insertInCommandMap(DeviceCommandId_t deviceCommand);
/**
* Enables a periodic reply for a given command. It sets to delay cycles to the specified
* maximum delay cycles for a given reply ID if enabled or to 0 if disabled.
* @param enable Specify whether to enable or disable a given periodic reply
* @return
*/
ReturnValue_t updatePeriodicReply(bool enable, DeviceCommandId_t deviceReply);
/**
* @brief This function returns the reply length of the next reply to read.
*
@ -493,16 +505,14 @@ protected:
virtual size_t getNextReplyLength(DeviceCommandId_t deviceCommand);
/**
* @brief This is a helper method to facilitate updating entries
* in the reply map.
* @brief This is a helper method to facilitate updating entries in the reply map.
* @param deviceCommand Identifier of the reply to update.
* @param delayCycles The current number of delay cycles to wait.
* As stated in #fillCommandAndCookieMap, to disable periodic commands,
* this is set to zero.
* @param delayCycles The current number of delay cycles to wait. As stated in
* #fillCommandAndReplyMap, to disable periodic commands, this is set to zero.
* @param maxDelayCycles The maximum number of delay cycles the reply waits
* until it times out. By passing 0 the entry remains untouched.
* @param periodic Indicates if the command is periodic (i.e. it is sent
* by the device repeatedly without request) or not.Default is aperiodic (0).
* by the device repeatedly without request) or not. Default is aperiodic (0).
* Warning: The setting always overrides the value that was entered in the map.
* @return - @c RETURN_OK when the command was successfully inserted,
* - @c RETURN_FAILED else.

View File

@ -120,7 +120,8 @@ public:
static const ReturnValue_t WRONG_MODE_FOR_COMMAND = MAKE_RETURN_CODE(0xA5);
static const ReturnValue_t TIMEOUT = MAKE_RETURN_CODE(0xA6);
static const ReturnValue_t BUSY = MAKE_RETURN_CODE(0xA7);
static const ReturnValue_t NO_REPLY_EXPECTED = MAKE_RETURN_CODE(0xA8); //!< Used to indicate that this is a command-only command.
//!< Used to indicate that this is a command-only command.
static const ReturnValue_t NO_REPLY_EXPECTED = MAKE_RETURN_CODE(0xA8);
static const ReturnValue_t NON_OP_TEMPERATURE = MAKE_RETURN_CODE(0xA9);
static const ReturnValue_t COMMAND_NOT_IMPLEMENTED = MAKE_RETURN_CODE(0xAA);

View File

@ -29,6 +29,8 @@ enum: uint8_t {
PUS_SERVICE_9 = 89,
PUS_SERVICE_17 = 97,
PUS_SERVICE_23 = 103,
MGM_LIS3MDL = 106,
MGM_RM3100 = 107,
FW_SUBSYSTEM_ID_RANGE
};

View File

@ -1,32 +1,13 @@
#include "fsfw/globalfunctions/DleEncoder.h"
DleEncoder::DleEncoder(bool escapeStxEtx, bool escapeCr): escapeStxEtx(escapeStxEtx),
escapeCr(escapeCr) {}
DleEncoder::DleEncoder(bool escapeStxEtx, bool escapeCr):
escapeStxEtx(escapeStxEtx), escapeCr(escapeCr) {}
DleEncoder::~DleEncoder() {}
ReturnValue_t DleEncoder::encode(const uint8_t* sourceStream,
size_t sourceLen, uint8_t* destStream, size_t maxDestLen,
size_t* encodedLen, bool addStxEtx) {
size_t minAllowedLen = 0;
if(escapeStxEtx) {
minAllowedLen = 2;
}
else {
minAllowedLen = 1;
}
if(maxDestLen < minAllowedLen) {
return STREAM_TOO_SHORT;
}
if (addStxEtx) {
if(not escapeStxEtx) {
destStream[0] = DLE_CHAR;
}
destStream[0] = STX_CHAR;
}
size_t sourceLen, uint8_t* destStream, size_t maxDestLen,
size_t* encodedLen, bool addStxEtx) {
if(escapeStxEtx) {
return encodeStreamEscaped(sourceStream, sourceLen,
destStream, maxDestLen, encodedLen, addStxEtx);
@ -41,9 +22,15 @@ ReturnValue_t DleEncoder::encode(const uint8_t* sourceStream,
ReturnValue_t DleEncoder::encodeStreamEscaped(const uint8_t *sourceStream, size_t sourceLen,
uint8_t *destStream, size_t maxDestLen, size_t *encodedLen,
bool addStxEtx) {
size_t encodedIndex = 1;
size_t encodedIndex = 0;
size_t sourceIndex = 0;
uint8_t nextByte = 0;
if(addStxEtx) {
if(maxDestLen < 1) {
return STREAM_TOO_SHORT;
}
destStream[encodedIndex++] = STX_CHAR;
}
while (encodedIndex < maxDestLen and sourceIndex < sourceLen) {
nextByte = sourceStream[sourceIndex];
// STX, ETX and CR characters in the stream need to be escaped with DLE
@ -83,8 +70,11 @@ ReturnValue_t DleEncoder::encodeStreamEscaped(const uint8_t *sourceStream, size_
++sourceIndex;
}
if (sourceIndex == sourceLen and encodedIndex < maxDestLen) {
if (sourceIndex == sourceLen) {
if (addStxEtx) {
if(encodedIndex + 1 >= maxDestLen) {
return STREAM_TOO_SHORT;
}
destStream[encodedIndex] = ETX_CHAR;
++encodedIndex;
}
@ -99,9 +89,16 @@ ReturnValue_t DleEncoder::encodeStreamEscaped(const uint8_t *sourceStream, size_
ReturnValue_t DleEncoder::encodeStreamNonEscaped(const uint8_t *sourceStream, size_t sourceLen,
uint8_t *destStream, size_t maxDestLen, size_t *encodedLen,
bool addStxEtx) {
size_t encodedIndex = 1;
size_t encodedIndex = 0;
size_t sourceIndex = 0;
uint8_t nextByte = 0;
if(addStxEtx) {
if(maxDestLen < 2) {
return STREAM_TOO_SHORT;
}
destStream[encodedIndex++] = DLE_CHAR;
destStream[encodedIndex++] = STX_CHAR;
}
while (encodedIndex < maxDestLen and sourceIndex < sourceLen) {
nextByte = sourceStream[sourceIndex];
// DLE characters are simply escaped with DLE.
@ -122,10 +119,13 @@ ReturnValue_t DleEncoder::encodeStreamNonEscaped(const uint8_t *sourceStream, si
++sourceIndex;
}
if (sourceIndex == sourceLen and encodedIndex < maxDestLen) {
if (sourceIndex == sourceLen) {
if (addStxEtx) {
destStream[encodedIndex] = ETX_CHAR;
++encodedIndex;
if(encodedIndex + 2 >= maxDestLen) {
return STREAM_TOO_SHORT;
}
destStream[encodedIndex++] = DLE_CHAR;
destStream[encodedIndex++] = ETX_CHAR;
}
*encodedLen = encodedIndex;
return RETURN_OK;
@ -136,40 +136,45 @@ ReturnValue_t DleEncoder::encodeStreamNonEscaped(const uint8_t *sourceStream, si
}
ReturnValue_t DleEncoder::decode(const uint8_t *sourceStream,
size_t sourceStreamLen, size_t *readLen, uint8_t *destStream,
size_t maxDestStreamlen, size_t *decodedLen) {
size_t encodedIndex = 0;
if(not escapeStxEtx) {
if (*sourceStream != DLE_CHAR) {
return DECODING_ERROR;
}
++encodedIndex;
}
if (sourceStream[encodedIndex] != STX_CHAR) {
return DECODING_ERROR;
}
if(escapeStxEtx) {
return decodeStreamEscaped(sourceStream, sourceStreamLen,
readLen, destStream, maxDestStreamlen, decodedLen);
}
else {
size_t sourceStreamLen, size_t *readLen, uint8_t *destStream,
size_t maxDestStreamlen, size_t *decodedLen) {
if(escapeStxEtx) {
return decodeStreamEscaped(sourceStream, sourceStreamLen,
readLen, destStream, maxDestStreamlen, decodedLen);
}
else {
return decodeStreamNonEscaped(sourceStream, sourceStreamLen,
readLen, destStream, maxDestStreamlen, decodedLen);
}
}
}
ReturnValue_t DleEncoder::decodeStreamEscaped(const uint8_t *sourceStream, size_t sourceStreamLen,
size_t *readLen, uint8_t *destStream,
size_t maxDestStreamlen, size_t *decodedLen) {
// Skip start marker, was already checked
size_t encodedIndex = 1;
size_t encodedIndex = 0;
size_t decodedIndex = 0;
uint8_t nextByte;
while ((encodedIndex < sourceStreamLen) && (decodedIndex < maxDestStreamlen)
&& (sourceStream[encodedIndex] != ETX_CHAR)
&& (sourceStream[encodedIndex] != STX_CHAR)) {
//init to 0 so that we can just return in the first checks (which do not consume anything from
//the source stream)
*readLen = 0;
if(maxDestStreamlen < 1) {
return STREAM_TOO_SHORT;
}
if (sourceStream[encodedIndex++] != STX_CHAR) {
return DECODING_ERROR;
}
while ((encodedIndex < sourceStreamLen)
and (decodedIndex < maxDestStreamlen)
and (sourceStream[encodedIndex] != ETX_CHAR)
and (sourceStream[encodedIndex] != STX_CHAR)) {
if (sourceStream[encodedIndex] == DLE_CHAR) {
if(encodedIndex + 1 >= sourceStreamLen) {
//reached the end of the sourceStream
*readLen = sourceStreamLen;
return DECODING_ERROR;
}
nextByte = sourceStream[encodedIndex + 1];
// The next byte is a DLE character that was escaped by another
// DLE character, so we can write it to the destination stream.
@ -186,6 +191,8 @@ ReturnValue_t DleEncoder::decodeStreamEscaped(const uint8_t *sourceStream, size_
destStream[decodedIndex] = nextByte - 0x40;
}
else {
// Set readLen so user can resume parsing after incorrect data
*readLen = encodedIndex + 2;
return DECODING_ERROR;
}
}
@ -199,8 +206,15 @@ ReturnValue_t DleEncoder::decodeStreamEscaped(const uint8_t *sourceStream, size_
++decodedIndex;
}
if (sourceStream[encodedIndex] != ETX_CHAR) {
*readLen = ++encodedIndex;
return DECODING_ERROR;
if(decodedIndex == maxDestStreamlen) {
//so far we did not find anything wrong here, so let user try again
*readLen = 0;
return STREAM_TOO_SHORT;
}
else {
*readLen = ++encodedIndex;
return DECODING_ERROR;
}
}
else {
*readLen = ++encodedIndex;
@ -212,15 +226,35 @@ ReturnValue_t DleEncoder::decodeStreamEscaped(const uint8_t *sourceStream, size_
ReturnValue_t DleEncoder::decodeStreamNonEscaped(const uint8_t *sourceStream,
size_t sourceStreamLen, size_t *readLen, uint8_t *destStream,
size_t maxDestStreamlen, size_t *decodedLen) {
// Skip start marker, was already checked
size_t encodedIndex = 2;
size_t encodedIndex = 0;
size_t decodedIndex = 0;
uint8_t nextByte;
//init to 0 so that we can just return in the first checks (which do not consume anything from
//the source stream)
*readLen = 0;
if(maxDestStreamlen < 2) {
return STREAM_TOO_SHORT;
}
if (sourceStream[encodedIndex++] != DLE_CHAR) {
return DECODING_ERROR;
}
if (sourceStream[encodedIndex++] != STX_CHAR) {
*readLen = 1;
return DECODING_ERROR;
}
while ((encodedIndex < sourceStreamLen) && (decodedIndex < maxDestStreamlen)) {
if (sourceStream[encodedIndex] == DLE_CHAR) {
if(encodedIndex + 1 >= sourceStreamLen) {
*readLen = encodedIndex;
return DECODING_ERROR;
}
nextByte = sourceStream[encodedIndex + 1];
if(nextByte == STX_CHAR) {
*readLen = ++encodedIndex;
// Set readLen so the DLE/STX char combination is preserved. Could be start of
// another frame
*readLen = encodedIndex;
return DECODING_ERROR;
}
else if(nextByte == DLE_CHAR) {
@ -235,6 +269,10 @@ ReturnValue_t DleEncoder::decodeStreamNonEscaped(const uint8_t *sourceStream,
*decodedLen = decodedIndex;
return RETURN_OK;
}
else {
*readLen = encodedIndex;
return DECODING_ERROR;
}
}
else {
destStream[decodedIndex] = sourceStream[encodedIndex];
@ -242,6 +280,17 @@ ReturnValue_t DleEncoder::decodeStreamNonEscaped(const uint8_t *sourceStream,
++encodedIndex;
++decodedIndex;
}
return DECODING_ERROR;
if(decodedIndex == maxDestStreamlen) {
//so far we did not find anything wrong here, so let user try again
*readLen = 0;
return STREAM_TOO_SHORT;
} else {
*readLen = encodedIndex;
return DECODING_ERROR;
}
}
void DleEncoder::setEscapeMode(bool escapeStxEtx) {
this->escapeStxEtx = escapeStxEtx;
}

View File

@ -37,6 +37,9 @@ public:
* @param escapeCr In escaped mode, escape all CR occurrences as well
*/
DleEncoder(bool escapeStxEtx = true, bool escapeCr = false);
void setEscapeMode(bool escapeStxEtx);
virtual ~DleEncoder();
static constexpr uint8_t INTERFACE_ID = CLASS_ID::DLE_ENCODER;
@ -68,6 +71,8 @@ public:
* @param addStxEtx Adding STX start marker and ETX end marker can be omitted,
* if they are added manually
* @return
* - RETURN_OK for successful encoding operation
* - STREAM_TOO_SHORT if the destination stream is too short
*/
ReturnValue_t encode(const uint8_t *sourceStream, size_t sourceLen,
uint8_t *destStream, size_t maxDestLen, size_t *encodedLen,
@ -82,6 +87,9 @@ public:
* @param maxDestStreamlen
* @param decodedLen
* @return
* - RETURN_OK for successful decode operation
* - DECODE_ERROR if the source stream is invalid
* - STREAM_TOO_SHORT if the destination stream is too short
*/
ReturnValue_t decode(const uint8_t *sourceStream,
size_t sourceStreamLen, size_t *readLen, uint8_t *destStream,

View File

@ -2,43 +2,42 @@
PeriodicOperationDivider::PeriodicOperationDivider(uint32_t divider,
bool resetAutomatically): resetAutomatically(resetAutomatically),
counter(divider), divider(divider) {
bool resetAutomatically): resetAutomatically(resetAutomatically),
counter(divider), divider(divider) {
}
bool PeriodicOperationDivider::checkAndIncrement() {
bool opNecessary = check();
if(opNecessary) {
if(resetAutomatically) {
counter = 0;
}
return opNecessary;
}
counter ++;
return opNecessary;
counter++;
bool opNecessary = check();
if(opNecessary) {
if(resetAutomatically) {
resetCounter();
}
}
return opNecessary;
}
bool PeriodicOperationDivider::check() {
if(counter >= divider) {
return true;
}
return false;
if(counter >= divider) {
return true;
}
return false;
}
void PeriodicOperationDivider::resetCounter() {
counter = 0;
counter = 0;
}
void PeriodicOperationDivider::setDivider(uint32_t newDivider) {
divider = newDivider;
divider = newDivider;
}
uint32_t PeriodicOperationDivider::getCounter() const {
return counter;
return counter;
}
uint32_t PeriodicOperationDivider::getDivider() const {
return divider;
return divider;
}

View File

@ -13,51 +13,51 @@
*/
class PeriodicOperationDivider {
public:
/**
* Initialize with the desired divider and specify whether the internal
* counter will be reset automatically.
* @param divider
* @param resetAutomatically
*/
PeriodicOperationDivider(uint32_t divider, bool resetAutomatically = true);
/**
* Initialize with the desired divider and specify whether the internal
* counter will be reset automatically.
* @param divider
* @param resetAutomatically
*/
PeriodicOperationDivider(uint32_t divider, bool resetAutomatically = true);
/**
* Check whether operation is necessary.
* If an operation is necessary and the class has been
* configured to be reset automatically, the counter will be reset.
*
* @return
* -@c true if the counter is larger or equal to the divider
* -@c false otherwise
*/
bool checkAndIncrement();
/**
* Check whether operation is necessary.
* If an operation is necessary and the class has been
* configured to be reset automatically, the counter will be reset.
*
* @return
* -@c true if the counter is larger or equal to the divider
* -@c false otherwise
*/
bool checkAndIncrement();
/**
* Checks whether an operation is necessary.
* This function will not increment the counter!
* @return
* -@c true if the counter is larger or equal to the divider
* -@c false otherwise
*/
bool check();
/**
* Checks whether an operation is necessary.
* This function will not increment the counter!
* @return
* -@c true if the counter is larger or equal to the divider
* -@c false otherwise
*/
bool check();
/**
* Can be used to reset the counter to 0 manually.
*/
void resetCounter();
uint32_t getCounter() const;
/**
* Can be used to reset the counter to 0 manually.
*/
void resetCounter();
uint32_t getCounter() const;
/**
* Can be used to set a new divider value.
* @param newDivider
*/
void setDivider(uint32_t newDivider);
uint32_t getDivider() const;
/**
* Can be used to set a new divider value.
* @param newDivider
*/
void setDivider(uint32_t newDivider);
uint32_t getDivider() const;
private:
bool resetAutomatically = true;
uint32_t counter = 0;
uint32_t divider = 0;
bool resetAutomatically = true;
uint32_t counter = 0;
uint32_t divider = 0;
};

View File

@ -1,8 +1,10 @@
#include "fsfw/osal/common/TcpTmTcServer.h"
#include "fsfw/osal/common/TcpTmTcBridge.h"
#include "fsfw/osal/common/tcpipHelpers.h"
#include "fsfw/platform.h"
#include "fsfw/FSFW.h"
#include "TcpTmTcServer.h"
#include "TcpTmTcBridge.h"
#include "tcpipHelpers.h"
#include "fsfw/container/SharedRingBuffer.h"
#include "fsfw/ipc/MessageQueueSenderIF.h"
#include "fsfw/ipc/MutexGuard.h"

View File

@ -285,10 +285,10 @@ ReturnValue_t MessageQueue::sendMessageFromMessageQueue(MessageQueueId_t sendTo,
utility::printUnixErrorGeneric(CLASS_NAME, "sendMessageFromMessageQueue", "EBADF");
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "mq_send to: " << sendTo << " sent from "
<< sentFrom << "failed" << std::endl;
sif::warning << "mq_send to " << sendTo << " sent from "
<< sentFrom << " failed" << std::endl;
#else
sif::printWarning("mq_send to: %d sent from %d failed\n", sendTo, sentFrom);
sif::printWarning("mq_send to %d sent from %d failed\n", sendTo, sentFrom);
#endif
return DESTINATION_INVALID;
}

View File

@ -41,8 +41,7 @@ ReturnValue_t Service5EventReporting::performService() {
}
}
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::debug << "Service5EventReporting::generateEventReport:"
" Too many events" << std::endl;
sif::warning << "Service5EventReporting::generateEventReport: Too many events" << std::endl;
#endif
return HasReturnvaluesIF::RETURN_OK;
}
@ -64,8 +63,11 @@ ReturnValue_t Service5EventReporting::generateEventReport(
requestQueue->getDefaultDestination(),requestQueue->getId());
if(result != HasReturnvaluesIF::RETURN_OK) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::debug << "Service5EventReporting::generateEventReport:"
" Could not send TM packet" << std::endl;
sif::warning << "Service5EventReporting::generateEventReport: "
"Could not send TM packet" << std::endl;
#else
sif::printWarning("Service5EventReporting::generateEventReport: "
"Could not send TM packet\n");
#endif
}
return result;

View File

@ -33,8 +33,8 @@ ReturnValue_t Service8FunctionManagement::getMessageQueueAndObject(
if(tcDataLen < sizeof(object_id_t)) {
return CommandingServiceBase::INVALID_TC;
}
SerializeAdapter::deSerialize(objectId, &tcData,
&tcDataLen, SerializeIF::Endianness::BIG);
// Can't fail, size was checked before
SerializeAdapter::deSerialize(objectId, &tcData, &tcDataLen, SerializeIF::Endianness::BIG);
return checkInterfaceAndAcquireMessageQueue(id,objectId);
}

View File

@ -13,10 +13,10 @@
/**
* @brief FailureReport class to serialize a failure report
* @brief Subservice 1, 3, 5, 7
* @brief Subservice 2, 4, 6, 8
* @ingroup spacepackets
*/
class FailureReport: public SerializeIF { //!< [EXPORT] : [SUBSERVICE] 1, 3, 5, 7
class FailureReport: public SerializeIF { //!< [EXPORT] : [SUBSERVICE] 2, 4, 6, 8
public:
FailureReport(uint8_t failureSubtype_, uint16_t packetId_,
uint16_t packetSequenceControl_, uint8_t stepNumber_,
@ -108,10 +108,10 @@ private:
};
/**
* @brief Subservices 2, 4, 6, 8
* @brief Subservices 1, 3, 5, 7
* @ingroup spacepackets
*/
class SuccessReport: public SerializeIF { //!< [EXPORT] : [SUBSERVICE] 2, 4, 6, 8
class SuccessReport: public SerializeIF { //!< [EXPORT] : [SUBSERVICE] 1, 3, 5, 7
public:
SuccessReport(uint8_t subtype_, uint16_t packetId_,
uint16_t packetSequenceControl_,uint8_t stepNumber_) :

View File

@ -77,6 +77,9 @@ enum: uint8_t {
HAL_UART, //HURT
HAL_I2C, //HI2C
HAL_GPIO, //HGIO
FIXED_SLOT_TASK_IF, //FTIF
MGM_LIS3MDL, //MGMLIS3
MGM_RM3100, //MGMRM3100
FW_CLASS_ID_COUNT // [EXPORT] : [END]
};

View File

@ -62,7 +62,8 @@ protected:
struct ChildInfo {
MessageQueueId_t commandQueue;
Mode_t mode;
Submode_t submode;bool healthChanged;
Submode_t submode;
bool healthChanged;
};
Mode_t mode;

View File

@ -1,4 +1,5 @@
#include "fsfw/tasks/FixedSlotSequence.h"
#include "fsfw/tasks/FixedTimeslotTaskIF.h"
#include "fsfw/serviceinterface/ServiceInterface.h"
#include <cstdlib>
@ -92,10 +93,9 @@ void FixedSlotSequence::addSlot(object_id_t componentId, uint32_t slotTimeMs,
ReturnValue_t FixedSlotSequence::checkSequence() const {
if(slotList.empty()) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::error << "FixedSlotSequence::checkSequence:"
<< " Slot list is empty!" << std::endl;
sif::warning << "FixedSlotSequence::checkSequence: Slot list is empty!" << std::endl;
#endif
return HasReturnvaluesIF::RETURN_FAILED;
return FixedTimeslotTaskIF::SLOT_LIST_EMPTY;
}
if(customCheckFunction != nullptr) {

View File

@ -2,7 +2,7 @@
#define FSFW_TASKS_FIXEDSLOTSEQUENCE_H_
#include "FixedSequenceSlot.h"
#include "../objectmanager/SystemObject.h"
#include "fsfw/objectmanager/SystemObject.h"
#include <set>
@ -136,6 +136,7 @@ public:
* @details
* Checks if timing is ok (must be ascending) and if all handlers were found.
* @return
* - SLOT_LIST_EMPTY if the slot list is empty
*/
ReturnValue_t checkSequence() const;
@ -147,6 +148,7 @@ public:
* The general check will be continued for now if the custom check function
* fails but a diagnostic debug output will be given.
* @param customCheckFunction
*
*/
void addCustomCheck(ReturnValue_t (*customCheckFunction)(const SlotList &));

View File

@ -2,7 +2,8 @@
#define FRAMEWORK_TASKS_FIXEDTIMESLOTTASKIF_H_
#include "PeriodicTaskIF.h"
#include "../objectmanager/ObjectManagerIF.h"
#include "fsfw/objectmanager/ObjectManagerIF.h"
#include "fsfw/returnvalues/FwClassIds.h"
/**
* @brief Following the same principle as the base class IF.
@ -12,6 +13,8 @@ class FixedTimeslotTaskIF : public PeriodicTaskIF {
public:
virtual ~FixedTimeslotTaskIF() {}
static constexpr ReturnValue_t SLOT_LIST_EMPTY = HasReturnvaluesIF::makeReturnCode(
CLASS_ID::FIXED_SLOT_TASK_IF, 0);
/**
* Add an object with a slot time and the execution step to the task.
* The execution step will be passed to the object (e.g. as an operation

View File

@ -3,8 +3,8 @@
#include <cstring>
SpacePacketBase::SpacePacketBase( const uint8_t* set_address ) {
this->data = (SpacePacketPointer*) set_address;
SpacePacketBase::SpacePacketBase(const uint8_t* setAddress) {
this->data = reinterpret_cast<SpacePacketPointer*>(const_cast<uint8_t*>(setAddress));
}
SpacePacketBase::~SpacePacketBase() {
@ -15,10 +15,21 @@ uint8_t SpacePacketBase::getPacketVersionNumber( void ) {
return (this->data->header.packet_id_h & 0b11100000) >> 5;
}
void SpacePacketBase::initSpacePacketHeader(bool isTelecommand,
ReturnValue_t SpacePacketBase::initSpacePacketHeader(bool isTelecommand,
bool hasSecondaryHeader, uint16_t apid, uint16_t sequenceCount) {
if(data == nullptr) {
#if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "SpacePacketBase::initSpacePacketHeader: Data pointer is invalid"
<< std::endl;
#else
sif::printWarning("SpacePacketBase::initSpacePacketHeader: Data pointer is invalid!\n");
#endif
#endif
return HasReturnvaluesIF::RETURN_FAILED;
}
//reset header to zero:
memset(data,0, sizeof(this->data->header) );
memset(data, 0, sizeof(this->data->header) );
//Set TC/TM bit.
data->header.packet_id_h = ((isTelecommand? 1 : 0)) << 4;
//Set secondaryHeader bit
@ -27,7 +38,7 @@ void SpacePacketBase::initSpacePacketHeader(bool isTelecommand,
//Always initialize as standalone packets.
data->header.sequence_control_h = 0b11000000;
setPacketSequenceCount(sequenceCount);
return HasReturnvaluesIF::RETURN_OK;
}
bool SpacePacketBase::isTelecommand( void ) {
@ -54,6 +65,11 @@ void SpacePacketBase::setAPID( uint16_t new_apid ) {
this->data->header.packet_id_l = ( new_apid & 0x00FF );
}
void SpacePacketBase::setSequenceFlags( uint8_t sequenceflags ) {
this->data->header.sequence_control_h &= 0x3F;
this->data->header.sequence_control_h |= sequenceflags << 6;
}
uint16_t SpacePacketBase::getPacketSequenceControl( void ) {
return ( (this->data->header.sequence_control_h) << 8 )
+ this->data->header.sequence_control_l;

View File

@ -2,6 +2,8 @@
#define FSFW_TMTCPACKET_SPACEPACKETBASE_H_
#include "ccsds_header.h"
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
#include <cstddef>
/**
@ -82,7 +84,7 @@ public:
*/
bool isTelecommand( void );
void initSpacePacketHeader(bool isTelecommand, bool hasSecondaryHeader,
ReturnValue_t initSpacePacketHeader(bool isTelecommand, bool hasSecondaryHeader,
uint16_t apid, uint16_t sequenceCount = 0);
/**
* The CCSDS header provides a secondary header flag (the fifth-highest bit),
@ -109,6 +111,13 @@ public:
* ignored.
*/
void setAPID( uint16_t setAPID );
/**
* Sets the sequence flags of a packet, which are bit 17 and 18 in the space packet header.
* @param The sequence flags to set
*/
void setSequenceFlags( uint8_t sequenceflags );
/**
* Returns the CCSDS packet sequence control field, which are the third and
* the fourth byte of the CCSDS primary header.

View File

@ -53,11 +53,14 @@ uint8_t* TmPacketPusC::getPacketTimeRaw() const{
}
void TmPacketPusC::initializeTmPacket(uint16_t apid, uint8_t service,
ReturnValue_t TmPacketPusC::initializeTmPacket(uint16_t apid, uint8_t service,
uint8_t subservice, uint16_t packetSubcounter, uint16_t destinationId,
uint8_t timeRefField) {
//Set primary header:
initSpacePacketHeader(false, true, apid);
ReturnValue_t result = initSpacePacketHeader(false, true, apid);
if(result != HasReturnvaluesIF::RETURN_OK) {
return result;
}
//Set data Field Header:
//First, set to zero.
memset(&tmData->dataField, 0, sizeof(tmData->dataField));
@ -76,6 +79,7 @@ void TmPacketPusC::initializeTmPacket(uint16_t apid, uint8_t service,
timeStamper->addTimeStamp(tmData->dataField.time,
sizeof(tmData->dataField.time));
}
return HasReturnvaluesIF::RETURN_OK;
}
void TmPacketPusC::setSourceDataSize(uint16_t size) {

View File

@ -100,7 +100,7 @@ protected:
* @param subservice PUS Subservice
* @param packetSubcounter Additional subcounter used.
*/
void initializeTmPacket(uint16_t apid, uint8_t service, uint8_t subservice,
ReturnValue_t initializeTmPacket(uint16_t apid, uint8_t service, uint8_t subservice,
uint16_t packetSubcounter, uint16_t destinationId = 0, uint8_t timeRefField = 0);
/**

View File

@ -43,27 +43,55 @@ TmPacketStoredPusC::TmPacketStoredPusC(uint16_t apid, uint8_t service,
return;
}
size_t sourceDataSize = 0;
if (content != NULL) {
if (content != nullptr) {
sourceDataSize += content->getSerializedSize();
}
if (header != NULL) {
if (header != nullptr) {
sourceDataSize += header->getSerializedSize();
}
uint8_t *p_data = NULL;
ReturnValue_t returnValue = store->getFreeElement(&storeAddress,
(getPacketMinimumSize() + sourceDataSize), &p_data);
uint8_t *pData = nullptr;
size_t sizeToReserve = getPacketMinimumSize() + sourceDataSize;
ReturnValue_t returnValue = store->getFreeElement(&storeAddress, sizeToReserve, &pData);
if (returnValue != store->RETURN_OK) {
#if FSFW_VERBOSE_LEVEL >= 1
switch(returnValue) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
case(StorageManagerIF::DATA_STORAGE_FULL): {
sif::warning << "TmPacketStoredPusC::TmPacketStoredPusC: Store full for packet with "
"size " << sizeToReserve << std::endl;
break;
}
case(StorageManagerIF::DATA_TOO_LARGE): {
sif::warning << "TmPacketStoredPusC::TmPacketStoredPusC: Data with size " <<
sizeToReserve << " too large" << std::endl;
break;
}
#else
case(StorageManagerIF::DATA_STORAGE_FULL): {
sif::printWarning("TmPacketStoredPusC::TmPacketStoredPusC: Store full for packet with "
"size %d\n", sizeToReserve);
break;
}
case(StorageManagerIF::DATA_TOO_LARGE): {
sif::printWarning("TmPacketStoredPusC::TmPacketStoredPusC: Data with size "
"%d too large\n", sizeToReserve);
break;
}
#endif
#endif
}
TmPacketStoredBase::checkAndReportLostTm();
return;
}
setData(p_data);
setData(pData);
initializeTmPacket(apid, service, subservice, packetSubcounter, destinationId, timeRefField);
uint8_t *putDataHere = getSourceData();
size_t size = 0;
if (header != NULL) {
if (header != nullptr) {
header->serialize(&putDataHere, &size, sourceDataSize,
SerializeIF::Endianness::BIG);
}
if (content != NULL) {
if (content != nullptr) {
content->serialize(&putDataHere, &size, sourceDataSize,
SerializeIF::Endianness::BIG);
}

View File

@ -19,7 +19,7 @@ class TmTcBridge : public AcceptsTelemetryIF,
public:
static constexpr uint8_t TMTC_RECEPTION_QUEUE_DEPTH = 20;
static constexpr uint8_t LIMIT_STORED_DATA_SENT_PER_CYCLE = 15;
static constexpr uint8_t LIMIT_DOWNLINK_PACKETS_STORED = 20;
static constexpr uint8_t LIMIT_DOWNLINK_PACKETS_STORED = 200;
static constexpr uint8_t DEFAULT_STORED_DATA_SENT_PER_CYCLE = 5;
static constexpr uint8_t DEFAULT_DOWNLINK_PACKETS_STORED = 10;

View File

@ -4,66 +4,219 @@
#include <array>
const std::array<uint8_t, 5> TEST_ARRAY_0 = { 0 };
const std::array<uint8_t, 3> TEST_ARRAY_1 = { 0, DleEncoder::DLE_CHAR, 5};
const std::array<uint8_t, 3> TEST_ARRAY_2 = { 0, DleEncoder::STX_CHAR, 5};
const std::array<uint8_t, 3> TEST_ARRAY_3 = { 0, DleEncoder::CARRIAGE_RETURN, DleEncoder::ETX_CHAR};
const std::vector<uint8_t> TEST_ARRAY_0 = { 0, 0, 0, 0, 0 };
const std::vector<uint8_t> TEST_ARRAY_1 = { 0, DleEncoder::DLE_CHAR, 5};
const std::vector<uint8_t> TEST_ARRAY_2 = { 0, DleEncoder::STX_CHAR, 5};
const std::vector<uint8_t> TEST_ARRAY_3 = { 0, DleEncoder::CARRIAGE_RETURN, DleEncoder::ETX_CHAR};
const std::vector<uint8_t> TEST_ARRAY_4 = { DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR,
DleEncoder::STX_CHAR };
const std::vector<uint8_t> TEST_ARRAY_0_ENCODED_ESCAPED = {
DleEncoder::STX_CHAR, 0, 0, 0, 0, 0, DleEncoder::ETX_CHAR
};
const std::vector<uint8_t> TEST_ARRAY_0_ENCODED_NON_ESCAPED = {
DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, 0, 0, 0, 0, 0,
DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR
};
const std::vector<uint8_t> TEST_ARRAY_1_ENCODED_ESCAPED = {
DleEncoder::STX_CHAR, 0, DleEncoder::DLE_CHAR, DleEncoder::DLE_CHAR, 5, DleEncoder::ETX_CHAR
};
const std::vector<uint8_t> TEST_ARRAY_1_ENCODED_NON_ESCAPED = {
DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, 0, DleEncoder::DLE_CHAR, DleEncoder::DLE_CHAR,
5, DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR
};
const std::vector<uint8_t> TEST_ARRAY_2_ENCODED_ESCAPED = {
DleEncoder::STX_CHAR, 0, DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR + 0x40,
5, DleEncoder::ETX_CHAR
};
const std::vector<uint8_t> TEST_ARRAY_2_ENCODED_NON_ESCAPED = {
DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, 0,
DleEncoder::STX_CHAR, 5, DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR
};
const std::vector<uint8_t> TEST_ARRAY_3_ENCODED_ESCAPED = {
DleEncoder::STX_CHAR, 0, DleEncoder::CARRIAGE_RETURN,
DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR + 0x40, DleEncoder::ETX_CHAR
};
const std::vector<uint8_t> TEST_ARRAY_3_ENCODED_NON_ESCAPED = {
DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, 0,
DleEncoder::CARRIAGE_RETURN, DleEncoder::ETX_CHAR, DleEncoder::DLE_CHAR,
DleEncoder::ETX_CHAR
};
const std::vector<uint8_t> TEST_ARRAY_4_ENCODED_ESCAPED = {
DleEncoder::STX_CHAR, DleEncoder::DLE_CHAR, DleEncoder::DLE_CHAR,
DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR + 0x40, DleEncoder::DLE_CHAR,
DleEncoder::STX_CHAR + 0x40, DleEncoder::ETX_CHAR
};
const std::vector<uint8_t> TEST_ARRAY_4_ENCODED_NON_ESCAPED = {
DleEncoder::DLE_CHAR, DleEncoder::STX_CHAR, DleEncoder::DLE_CHAR, DleEncoder::DLE_CHAR,
DleEncoder::ETX_CHAR, DleEncoder::STX_CHAR, DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR
};
TEST_CASE("DleEncoder" , "[DleEncoder]") {
DleEncoder dleEncoder;
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
std::array<uint8_t, 32> buffer;
size_t encodedLen = 0;
size_t readLen = 0;
size_t decodedLen = 0;
auto testLambdaEncode = [&](DleEncoder& encoder, const std::vector<uint8_t>& vecToEncode,
const std::vector<uint8_t>& expectedVec) {
result = encoder.encode(vecToEncode.data(), vecToEncode.size(),
buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == retval::CATCH_OK);
for(size_t idx = 0; idx < expectedVec.size(); idx++) {
REQUIRE(buffer[idx] == expectedVec[idx]);
}
REQUIRE(encodedLen == expectedVec.size());
};
auto testLambdaDecode = [&](DleEncoder& encoder, const std::vector<uint8_t>& testVecEncoded,
const std::vector<uint8_t>& expectedVec) {
result = encoder.decode(testVecEncoded.data(),
testVecEncoded.size(),
&readLen, buffer.data(), buffer.size(), &decodedLen);
REQUIRE(result == retval::CATCH_OK);
REQUIRE(readLen == testVecEncoded.size());
REQUIRE(decodedLen == expectedVec.size());
for(size_t idx = 0; idx < decodedLen; idx++) {
REQUIRE(buffer[idx] == expectedVec[idx]);
}
};
SECTION("Encoding") {
size_t encodedLen = 0;
ReturnValue_t result = dleEncoder.encode(TEST_ARRAY_0.data(), TEST_ARRAY_0.size(),
buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == retval::CATCH_OK);
std::vector<uint8_t> expected = {DleEncoder::STX_CHAR, 0, 0, 0, 0, 0,
DleEncoder::ETX_CHAR};
for(size_t idx = 0; idx < expected.size(); idx++) {
REQUIRE(buffer[idx] == expected[idx]);
}
REQUIRE(encodedLen == 7);
testLambdaEncode(dleEncoder, TEST_ARRAY_0, TEST_ARRAY_0_ENCODED_ESCAPED);
testLambdaEncode(dleEncoder, TEST_ARRAY_1, TEST_ARRAY_1_ENCODED_ESCAPED);
testLambdaEncode(dleEncoder, TEST_ARRAY_2, TEST_ARRAY_2_ENCODED_ESCAPED);
testLambdaEncode(dleEncoder, TEST_ARRAY_3, TEST_ARRAY_3_ENCODED_ESCAPED);
testLambdaEncode(dleEncoder, TEST_ARRAY_4, TEST_ARRAY_4_ENCODED_ESCAPED);
result = dleEncoder.encode(TEST_ARRAY_1.data(), TEST_ARRAY_1.size(),
buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == retval::CATCH_OK);
expected = std::vector<uint8_t>{DleEncoder::STX_CHAR, 0, DleEncoder::DLE_CHAR,
DleEncoder::DLE_CHAR, 5, DleEncoder::ETX_CHAR};
for(size_t idx = 0; idx < expected.size(); idx++) {
REQUIRE(buffer[idx] == expected[idx]);
}
REQUIRE(encodedLen == expected.size());
auto testFaultyEncoding = [&](const std::vector<uint8_t>& vecToEncode,
const std::vector<uint8_t>& expectedVec) {
result = dleEncoder.encode(TEST_ARRAY_2.data(), TEST_ARRAY_2.size(),
buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == retval::CATCH_OK);
expected = std::vector<uint8_t>{DleEncoder::STX_CHAR, 0, DleEncoder::DLE_CHAR,
DleEncoder::STX_CHAR + 0x40, 5, DleEncoder::ETX_CHAR};
for(size_t idx = 0; idx < expected.size(); idx++) {
REQUIRE(buffer[idx] == expected[idx]);
}
REQUIRE(encodedLen == expected.size());
for(size_t faultyDestSize = 0; faultyDestSize < expectedVec.size(); faultyDestSize ++) {
result = dleEncoder.encode(vecToEncode.data(), vecToEncode.size(),
buffer.data(), faultyDestSize, &encodedLen);
REQUIRE(result == DleEncoder::STREAM_TOO_SHORT);
}
};
result = dleEncoder.encode(TEST_ARRAY_3.data(), TEST_ARRAY_3.size(),
buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == retval::CATCH_OK);
expected = std::vector<uint8_t>{DleEncoder::STX_CHAR, 0, DleEncoder::CARRIAGE_RETURN,
DleEncoder::DLE_CHAR, DleEncoder::ETX_CHAR + 0x40, DleEncoder::ETX_CHAR};
for(size_t idx = 0; idx < expected.size(); idx++) {
REQUIRE(buffer[idx] == expected[idx]);
}
REQUIRE(encodedLen == expected.size());
testFaultyEncoding(TEST_ARRAY_0, TEST_ARRAY_0_ENCODED_ESCAPED);
testFaultyEncoding(TEST_ARRAY_1, TEST_ARRAY_1_ENCODED_ESCAPED);
testFaultyEncoding(TEST_ARRAY_2, TEST_ARRAY_2_ENCODED_ESCAPED);
testFaultyEncoding(TEST_ARRAY_3, TEST_ARRAY_3_ENCODED_ESCAPED);
testFaultyEncoding(TEST_ARRAY_4, TEST_ARRAY_4_ENCODED_ESCAPED);
result = dleEncoder.encode(TEST_ARRAY_3.data(), TEST_ARRAY_3.size(),
buffer.data(), 0, &encodedLen);
REQUIRE(result == DleEncoder::STREAM_TOO_SHORT);
result = dleEncoder.encode(TEST_ARRAY_1.data(), TEST_ARRAY_1.size(),
buffer.data(), 4, &encodedLen);
REQUIRE(result == DleEncoder::STREAM_TOO_SHORT);
dleEncoder.setEscapeMode(false);
testLambdaEncode(dleEncoder, TEST_ARRAY_0, TEST_ARRAY_0_ENCODED_NON_ESCAPED);
testLambdaEncode(dleEncoder, TEST_ARRAY_1, TEST_ARRAY_1_ENCODED_NON_ESCAPED);
testLambdaEncode(dleEncoder, TEST_ARRAY_2, TEST_ARRAY_2_ENCODED_NON_ESCAPED);
testLambdaEncode(dleEncoder, TEST_ARRAY_3, TEST_ARRAY_3_ENCODED_NON_ESCAPED);
testLambdaEncode(dleEncoder, TEST_ARRAY_4, TEST_ARRAY_4_ENCODED_NON_ESCAPED);
testFaultyEncoding(TEST_ARRAY_0, TEST_ARRAY_0_ENCODED_NON_ESCAPED);
testFaultyEncoding(TEST_ARRAY_1, TEST_ARRAY_1_ENCODED_NON_ESCAPED);
testFaultyEncoding(TEST_ARRAY_2, TEST_ARRAY_2_ENCODED_NON_ESCAPED);
testFaultyEncoding(TEST_ARRAY_3, TEST_ARRAY_3_ENCODED_NON_ESCAPED);
testFaultyEncoding(TEST_ARRAY_4, TEST_ARRAY_4_ENCODED_NON_ESCAPED);
dleEncoder.setEscapeMode(true);
}
SECTION("Decoding") {
testLambdaDecode(dleEncoder, TEST_ARRAY_0_ENCODED_ESCAPED, TEST_ARRAY_0);
testLambdaDecode(dleEncoder, TEST_ARRAY_1_ENCODED_ESCAPED, TEST_ARRAY_1);
testLambdaDecode(dleEncoder, TEST_ARRAY_2_ENCODED_ESCAPED, TEST_ARRAY_2);
testLambdaDecode(dleEncoder, TEST_ARRAY_3_ENCODED_ESCAPED, TEST_ARRAY_3);
testLambdaDecode(dleEncoder, TEST_ARRAY_4_ENCODED_ESCAPED, TEST_ARRAY_4);
// Faulty source data
auto testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_ESCAPED;
testArray1EncodedFaulty[3] = 0;
result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(),
&readLen, buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == static_cast<int>(DleEncoder::DECODING_ERROR));
auto testArray2EncodedFaulty = TEST_ARRAY_2_ENCODED_ESCAPED;
testArray2EncodedFaulty[5] = 0;
result = dleEncoder.decode(testArray2EncodedFaulty.data(), testArray2EncodedFaulty.size(),
&readLen, buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == static_cast<int>(DleEncoder::DECODING_ERROR));
auto testArray4EncodedFaulty = TEST_ARRAY_4_ENCODED_ESCAPED;
testArray4EncodedFaulty[2] = 0;
result = dleEncoder.decode(testArray4EncodedFaulty.data(), testArray4EncodedFaulty.size(),
&readLen, buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == static_cast<int>(DleEncoder::DECODING_ERROR));
auto testArray4EncodedFaulty2 = TEST_ARRAY_4_ENCODED_ESCAPED;
testArray4EncodedFaulty2[4] = 0;
result = dleEncoder.decode(testArray4EncodedFaulty2.data(), testArray4EncodedFaulty2.size(),
&readLen, buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == static_cast<int>(DleEncoder::DECODING_ERROR));
auto testFaultyDecoding = [&](const std::vector<uint8_t>& vecToDecode,
const std::vector<uint8_t>& expectedVec) {
for(size_t faultyDestSizes = 0;
faultyDestSizes < expectedVec.size();
faultyDestSizes ++) {
result = dleEncoder.decode(vecToDecode.data(),
vecToDecode.size(), &readLen,
buffer.data(), faultyDestSizes, &decodedLen);
REQUIRE(result == static_cast<int>(DleEncoder::STREAM_TOO_SHORT));
}
};
testFaultyDecoding(TEST_ARRAY_0_ENCODED_ESCAPED, TEST_ARRAY_0);
testFaultyDecoding(TEST_ARRAY_1_ENCODED_ESCAPED, TEST_ARRAY_1);
testFaultyDecoding(TEST_ARRAY_2_ENCODED_ESCAPED, TEST_ARRAY_2);
testFaultyDecoding(TEST_ARRAY_3_ENCODED_ESCAPED, TEST_ARRAY_3);
testFaultyDecoding(TEST_ARRAY_4_ENCODED_ESCAPED, TEST_ARRAY_4);
dleEncoder.setEscapeMode(false);
testLambdaDecode(dleEncoder, TEST_ARRAY_0_ENCODED_NON_ESCAPED, TEST_ARRAY_0);
testLambdaDecode(dleEncoder, TEST_ARRAY_1_ENCODED_NON_ESCAPED, TEST_ARRAY_1);
testLambdaDecode(dleEncoder, TEST_ARRAY_2_ENCODED_NON_ESCAPED, TEST_ARRAY_2);
testLambdaDecode(dleEncoder, TEST_ARRAY_3_ENCODED_NON_ESCAPED, TEST_ARRAY_3);
testLambdaDecode(dleEncoder, TEST_ARRAY_4_ENCODED_NON_ESCAPED, TEST_ARRAY_4);
testFaultyDecoding(TEST_ARRAY_0_ENCODED_NON_ESCAPED, TEST_ARRAY_0);
testFaultyDecoding(TEST_ARRAY_1_ENCODED_NON_ESCAPED, TEST_ARRAY_1);
testFaultyDecoding(TEST_ARRAY_2_ENCODED_NON_ESCAPED, TEST_ARRAY_2);
testFaultyDecoding(TEST_ARRAY_3_ENCODED_NON_ESCAPED, TEST_ARRAY_3);
testFaultyDecoding(TEST_ARRAY_4_ENCODED_NON_ESCAPED, TEST_ARRAY_4);
// Faulty source data
testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_NON_ESCAPED;
auto prevVal = testArray1EncodedFaulty[0];
testArray1EncodedFaulty[0] = 0;
result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(),
&readLen, buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == static_cast<int>(DleEncoder::DECODING_ERROR));
testArray1EncodedFaulty[0] = prevVal;
testArray1EncodedFaulty[1] = 0;
result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(),
&readLen, buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == static_cast<int>(DleEncoder::DECODING_ERROR));
testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_NON_ESCAPED;
testArray1EncodedFaulty[6] = 0;
result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(),
&readLen, buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == static_cast<int>(DleEncoder::DECODING_ERROR));
testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_NON_ESCAPED;
testArray1EncodedFaulty[7] = 0;
result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(),
&readLen, buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == static_cast<int>(DleEncoder::DECODING_ERROR));
testArray4EncodedFaulty = TEST_ARRAY_4_ENCODED_NON_ESCAPED;
testArray4EncodedFaulty[3] = 0;
result = dleEncoder.decode(testArray4EncodedFaulty.data(), testArray4EncodedFaulty.size(),
&readLen, buffer.data(), buffer.size(), &encodedLen);
REQUIRE(result == static_cast<int>(DleEncoder::DECODING_ERROR));
dleEncoder.setEscapeMode(true);
}
}