Compare commits
72 Commits
3d1be94e12
...
v2.0.1
Author | SHA1 | Date | |
---|---|---|---|
e6a7108614 | |||
08926f9b70 | |||
52f0c29e99 | |||
d2371b3e71 | |||
ffa38a81b7 | |||
ae689408f3 | |||
155432663b | |||
ecdbf98ca4 | |||
54a6c1b0aa | |||
9efe9e78d8 | |||
ab906fa534 | |||
146e1e3282 | |||
f11957d827 | |||
a977302a53 | |||
53400c8bfa | |||
f2d0a0d9ee | |||
9e12f59707 | |||
2439613f21 | |||
1c8f86364d | |||
4e1c52f465 | |||
9f856761e2 | |||
2f119f102d | |||
afb472996c | |||
f76f462022 | |||
0f90d50065 | |||
b0cbd40e64 | |||
1c1433e797 | |||
7671c93095 | |||
ba4249d658 | |||
de7542c9c1 | |||
5a30dd969f | |||
0a2c912f29 | |||
2b15f9e644 | |||
42b5f8a79d | |||
358ee0fbf2 | |||
4f08b2d342 | |||
4b62c8aa81 | |||
1b38f84edc | |||
5064d44999 | |||
322c14d4bb | |||
8ec35f158c | |||
9a25f08fef | |||
f3caa122ae | |||
6e88f8f400 | |||
01762ad222 | |||
71d66c406f | |||
42df77ff32 | |||
85c04dee23 | |||
4c96db847d | |||
0246dccbe9 | |||
423f7c8281 | |||
59feaa4b5c | |||
a84e60a37a | |||
061d79bb62 | |||
a37b6184fc | |||
![]() |
f6b03dee6a | ||
a6bd7c0d6e | |||
f2bc374f0f | |||
52b3d9473e | |||
fc9b85d5db | |||
bfae25ff2d | |||
ea3812fbbd | |||
f40f783cb4 | |||
9429f6b868 | |||
39c909946b | |||
01c833f001 | |||
7c21980ece | |||
3e3c38e459 | |||
e5db64cbb9 | |||
21b5eaa891 | |||
ca65daab1a | |||
517d52f55d |
@@ -1,13 +1,15 @@
|
|||||||
#include "fsfw_hal/devicehandlers/GyroL3GD20Handler.h"
|
#include "GyroL3GD20Handler.h"
|
||||||
|
|
||||||
#include "fsfw/datapool/PoolReadGuard.h"
|
#include "fsfw/datapool/PoolReadGuard.h"
|
||||||
|
|
||||||
|
#include <cmath>
|
||||||
|
|
||||||
GyroHandlerL3GD20H::GyroHandlerL3GD20H(object_id_t objectId, object_id_t deviceCommunication,
|
GyroHandlerL3GD20H::GyroHandlerL3GD20H(object_id_t objectId, object_id_t deviceCommunication,
|
||||||
CookieIF *comCookie, uint8_t switchId, uint32_t transitionDelayMs):
|
CookieIF *comCookie, uint32_t transitionDelayMs):
|
||||||
DeviceHandlerBase(objectId, deviceCommunication, comCookie),
|
DeviceHandlerBase(objectId, deviceCommunication, comCookie),
|
||||||
switchId(switchId), transitionDelayMs(transitionDelayMs), dataset(this) {
|
transitionDelayMs(transitionDelayMs), dataset(this) {
|
||||||
#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1
|
#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1
|
||||||
debugDivider = new PeriodicOperationDivider(5);
|
debugDivider = new PeriodicOperationDivider(3);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -215,11 +217,32 @@ ReturnValue_t GyroHandlerL3GD20H::interpretDeviceReply(DeviceCommandId_t id,
|
|||||||
|
|
||||||
PoolReadGuard readSet(&dataset);
|
PoolReadGuard readSet(&dataset);
|
||||||
if(readSet.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
|
if(readSet.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
if(std::abs(angVelocX) < this->absLimitX) {
|
||||||
dataset.angVelocX = angVelocX;
|
dataset.angVelocX = angVelocX;
|
||||||
|
dataset.angVelocX.setValid(true);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
dataset.angVelocX.setValid(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(std::abs(angVelocY) < this->absLimitY) {
|
||||||
dataset.angVelocY = angVelocY;
|
dataset.angVelocY = angVelocY;
|
||||||
|
dataset.angVelocY.setValid(true);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
dataset.angVelocY.setValid(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(std::abs(angVelocZ) < this->absLimitZ) {
|
||||||
dataset.angVelocZ = angVelocZ;
|
dataset.angVelocZ = angVelocZ;
|
||||||
|
dataset.angVelocZ.setValid(true);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
dataset.angVelocZ.setValid(false);
|
||||||
|
}
|
||||||
|
|
||||||
dataset.temperature = temperature;
|
dataset.temperature = temperature;
|
||||||
dataset.setValidity(true, true);
|
dataset.temperature.setValid(true);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@@ -234,7 +257,7 @@ uint32_t GyroHandlerL3GD20H::getTransitionDelayMs(Mode_t from, Mode_t to) {
|
|||||||
return this->transitionDelayMs;
|
return this->transitionDelayMs;
|
||||||
}
|
}
|
||||||
|
|
||||||
void GyroHandlerL3GD20H::setGoNormalModeAtStartup() {
|
void GyroHandlerL3GD20H::setToGoToNormalMode(bool enable) {
|
||||||
this->goNormalModeImmediately = true;
|
this->goNormalModeImmediately = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -256,3 +279,9 @@ void GyroHandlerL3GD20H::fillCommandAndReplyMap() {
|
|||||||
void GyroHandlerL3GD20H::modeChanged() {
|
void GyroHandlerL3GD20H::modeChanged() {
|
||||||
internalState = InternalState::NONE;
|
internalState = InternalState::NONE;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void GyroHandlerL3GD20H::setAbsoluteLimits(float limitX, float limitY, float limitZ) {
|
||||||
|
this->absLimitX = limitX;
|
||||||
|
this->absLimitY = limitY;
|
||||||
|
this->absLimitZ = limitZ;
|
||||||
|
}
|
||||||
|
@@ -19,13 +19,22 @@
|
|||||||
class GyroHandlerL3GD20H: public DeviceHandlerBase {
|
class GyroHandlerL3GD20H: public DeviceHandlerBase {
|
||||||
public:
|
public:
|
||||||
GyroHandlerL3GD20H(object_id_t objectId, object_id_t deviceCommunication,
|
GyroHandlerL3GD20H(object_id_t objectId, object_id_t deviceCommunication,
|
||||||
CookieIF* comCookie, uint8_t switchId, uint32_t transitionDelayMs = 10000);
|
CookieIF* comCookie, uint32_t transitionDelayMs);
|
||||||
virtual ~GyroHandlerL3GD20H();
|
virtual ~GyroHandlerL3GD20H();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* 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
|
* @brief Configure device handler to go to normal mode immediately
|
||||||
*/
|
*/
|
||||||
void setGoNormalModeAtStartup();
|
void setToGoToNormalMode(bool enable);
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
/* DeviceHandlerBase overrides */
|
/* DeviceHandlerBase overrides */
|
||||||
@@ -40,20 +49,23 @@ protected:
|
|||||||
size_t commandDataLen) override;
|
size_t commandDataLen) override;
|
||||||
ReturnValue_t scanForReply(const uint8_t *start, size_t len,
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len,
|
||||||
DeviceCommandId_t *foundId, size_t *foundLen) override;
|
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;
|
const uint8_t *packet) override;
|
||||||
|
|
||||||
void fillCommandAndReplyMap() override;
|
void fillCommandAndReplyMap() override;
|
||||||
void modeChanged() 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,
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
LocalDataPoolManager &poolManager) override;
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
uint8_t switchId = 0;
|
|
||||||
uint32_t transitionDelayMs = 0;
|
uint32_t transitionDelayMs = 0;
|
||||||
GyroPrimaryDataset dataset;
|
GyroPrimaryDataset dataset;
|
||||||
|
|
||||||
|
float absLimitX = L3GD20H::RANGE_DPS_00;
|
||||||
|
float absLimitY = L3GD20H::RANGE_DPS_00;
|
||||||
|
float absLimitZ = L3GD20H::RANGE_DPS_00;
|
||||||
|
|
||||||
enum class InternalState {
|
enum class InternalState {
|
||||||
NONE,
|
NONE,
|
||||||
CONFIGURE,
|
CONFIGURE,
|
||||||
|
@@ -5,14 +5,16 @@
|
|||||||
#include "fsfw/globalfunctions/PeriodicOperationDivider.h"
|
#include "fsfw/globalfunctions/PeriodicOperationDivider.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#include <cmath>
|
||||||
|
|
||||||
MgmLIS3MDLHandler::MgmLIS3MDLHandler(object_id_t objectId, object_id_t deviceCommunication,
|
MgmLIS3MDLHandler::MgmLIS3MDLHandler(object_id_t objectId, object_id_t deviceCommunication,
|
||||||
CookieIF* comCookie, uint8_t switchId, uint32_t transitionDelay):
|
CookieIF* comCookie, uint32_t transitionDelay):
|
||||||
DeviceHandlerBase(objectId, deviceCommunication, comCookie),
|
DeviceHandlerBase(objectId, deviceCommunication, comCookie),
|
||||||
dataset(this), transitionDelay(transitionDelay) {
|
dataset(this), transitionDelay(transitionDelay) {
|
||||||
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
|
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
|
||||||
debugDivider = new PeriodicOperationDivider(5);
|
debugDivider = new PeriodicOperationDivider(3);
|
||||||
#endif
|
#endif
|
||||||
/* Set to default values right away. */
|
// Set to default values right away
|
||||||
registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT;
|
registers[0] = MGMLIS3MDL::CTRL_REG1_DEFAULT;
|
||||||
registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT;
|
registers[1] = MGMLIS3MDL::CTRL_REG2_DEFAULT;
|
||||||
registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT;
|
registers[2] = MGMLIS3MDL::CTRL_REG3_DEFAULT;
|
||||||
@@ -291,7 +293,6 @@ ReturnValue_t MgmLIS3MDLHandler::interpretDeviceReply(DeviceCommandId_t id,
|
|||||||
|
|
||||||
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
|
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
|
||||||
if(debugDivider->checkAndIncrement()) {
|
if(debugDivider->checkAndIncrement()) {
|
||||||
/* Set terminal to utf-8 if there is an issue with micro printout. */
|
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||||
sif::info << "MGMHandlerLIS3: Magnetic field strength in"
|
sif::info << "MGMHandlerLIS3: Magnetic field strength in"
|
||||||
" microtesla:" << std::endl;
|
" microtesla:" << std::endl;
|
||||||
@@ -308,10 +309,29 @@ ReturnValue_t MgmLIS3MDLHandler::interpretDeviceReply(DeviceCommandId_t id,
|
|||||||
#endif /* OBSW_VERBOSE_LEVEL >= 1 */
|
#endif /* OBSW_VERBOSE_LEVEL >= 1 */
|
||||||
PoolReadGuard readHelper(&dataset);
|
PoolReadGuard readHelper(&dataset);
|
||||||
if(readHelper.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
|
if(readHelper.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
|
||||||
|
if(std::abs(mgmX) < absLimitX) {
|
||||||
dataset.fieldStrengthX = mgmX;
|
dataset.fieldStrengthX = mgmX;
|
||||||
|
dataset.fieldStrengthX.setValid(true);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
dataset.fieldStrengthX.setValid(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(std::abs(mgmY) < absLimitY) {
|
||||||
dataset.fieldStrengthY = mgmY;
|
dataset.fieldStrengthY = mgmY;
|
||||||
|
dataset.fieldStrengthY.setValid(true);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
dataset.fieldStrengthY.setValid(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
if(std::abs(mgmZ) < absLimitZ) {
|
||||||
dataset.fieldStrengthZ = mgmZ;
|
dataset.fieldStrengthZ = mgmZ;
|
||||||
dataset.setValidity(true, true);
|
dataset.fieldStrengthZ.setValid(true);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
dataset.fieldStrengthZ.setValid(false);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@@ -321,7 +341,6 @@ ReturnValue_t MgmLIS3MDLHandler::interpretDeviceReply(DeviceCommandId_t id,
|
|||||||
float tempValue = 25.0 + ((static_cast<float>(tempValueRaw)) / 8.0);
|
float tempValue = 25.0 + ((static_cast<float>(tempValueRaw)) / 8.0);
|
||||||
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
|
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
|
||||||
if(debugDivider->check()) {
|
if(debugDivider->check()) {
|
||||||
/* Set terminal to utf-8 if there is an issue with micro printout. */
|
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||||
sif::info << "MGMHandlerLIS3: Temperature: " << tempValue << " C" <<
|
sif::info << "MGMHandlerLIS3: Temperature: " << tempValue << " C" <<
|
||||||
std::endl;
|
std::endl;
|
||||||
@@ -444,16 +463,6 @@ ReturnValue_t MgmLIS3MDLHandler::setOperatingMode(const uint8_t *commandData,
|
|||||||
}
|
}
|
||||||
|
|
||||||
void MgmLIS3MDLHandler::fillCommandAndReplyMap() {
|
void MgmLIS3MDLHandler::fillCommandAndReplyMap() {
|
||||||
/*
|
|
||||||
* Regarding ArduinoBoard:
|
|
||||||
* Actually SPI answers directly, but as commanding ArduinoBoard the
|
|
||||||
* communication could be delayed
|
|
||||||
* SPI always has to be triggered, so there could be no periodic answer of
|
|
||||||
* the device, the device has to asked with a command, so periodic is zero.
|
|
||||||
*
|
|
||||||
* We dont read single registers, we just expect special
|
|
||||||
* reply from he Readall_MGM
|
|
||||||
*/
|
|
||||||
insertInCommandAndReplyMap(MGMLIS3MDL::READ_CONFIG_AND_DATA, 1, &dataset);
|
insertInCommandAndReplyMap(MGMLIS3MDL::READ_CONFIG_AND_DATA, 1, &dataset);
|
||||||
insertInCommandAndReplyMap(MGMLIS3MDL::READ_TEMPERATURE, 1);
|
insertInCommandAndReplyMap(MGMLIS3MDL::READ_TEMPERATURE, 1);
|
||||||
insertInCommandAndReplyMap(MGMLIS3MDL::SETUP_MGM, 1);
|
insertInCommandAndReplyMap(MGMLIS3MDL::SETUP_MGM, 1);
|
||||||
@@ -475,7 +484,7 @@ ReturnValue_t MgmLIS3MDLHandler::prepareCtrlRegisterWrite() {
|
|||||||
rawPacket = commandBuffer;
|
rawPacket = commandBuffer;
|
||||||
rawPacketLen = MGMLIS3MDL::NR_OF_CTRL_REGISTERS + 1;
|
rawPacketLen = MGMLIS3MDL::NR_OF_CTRL_REGISTERS + 1;
|
||||||
|
|
||||||
/* We dont have to check if this is working because we just did it */
|
// We dont have to check if this is working because we just did i
|
||||||
return RETURN_OK;
|
return RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -503,3 +512,9 @@ ReturnValue_t MgmLIS3MDLHandler::initializeLocalDataPool(
|
|||||||
new PoolEntry<float>({0.0}));
|
new PoolEntry<float>({0.0}));
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void MgmLIS3MDLHandler::setAbsoluteLimits(float xLimit, float yLimit, float zLimit) {
|
||||||
|
this->absLimitX = xLimit;
|
||||||
|
this->absLimitY = yLimit;
|
||||||
|
this->absLimitZ = zLimit;
|
||||||
|
}
|
||||||
|
@@ -31,9 +31,17 @@ public:
|
|||||||
static const Event CHANGE_OF_SETUP_PARAMETER = MAKE_EVENT(0, severity::LOW);
|
static const Event CHANGE_OF_SETUP_PARAMETER = MAKE_EVENT(0, severity::LOW);
|
||||||
|
|
||||||
MgmLIS3MDLHandler(uint32_t objectId, object_id_t deviceCommunication, CookieIF* comCookie,
|
MgmLIS3MDLHandler(uint32_t objectId, object_id_t deviceCommunication, CookieIF* comCookie,
|
||||||
uint8_t switchId, uint32_t transitionDelay = 10000);
|
uint32_t transitionDelay);
|
||||||
virtual ~MgmLIS3MDLHandler();
|
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);
|
void setToGoToNormalMode(bool enable);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
@@ -42,7 +50,7 @@ protected:
|
|||||||
void doShutDown() override;
|
void doShutDown() override;
|
||||||
void doStartUp() override;
|
void doStartUp() override;
|
||||||
void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override;
|
void doTransition(Mode_t modeFrom, Submode_t subModeFrom) override;
|
||||||
uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override;
|
virtual uint32_t getTransitionDelayMs(Mode_t from, Mode_t to) override;
|
||||||
ReturnValue_t buildCommandFromCommand(
|
ReturnValue_t buildCommandFromCommand(
|
||||||
DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
||||||
size_t commandDataLen) override;
|
size_t commandDataLen) override;
|
||||||
@@ -52,7 +60,14 @@ protected:
|
|||||||
DeviceCommandId_t *id) override;
|
DeviceCommandId_t *id) override;
|
||||||
ReturnValue_t scanForReply(const uint8_t *start, size_t len,
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len,
|
||||||
DeviceCommandId_t *foundId, size_t *foundLen) override;
|
DeviceCommandId_t *foundId, size_t *foundLen) override;
|
||||||
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id,
|
/**
|
||||||
|
* 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;
|
const uint8_t *packet) override;
|
||||||
void fillCommandAndReplyMap() override;
|
void fillCommandAndReplyMap() override;
|
||||||
void modeChanged(void) override;
|
void modeChanged(void) override;
|
||||||
@@ -61,15 +76,19 @@ protected:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
MGMLIS3MDL::MgmPrimaryDataset dataset;
|
MGMLIS3MDL::MgmPrimaryDataset dataset;
|
||||||
//Length a sindgle command SPI answer
|
//Length a single command SPI answer
|
||||||
static const uint8_t SINGLE_COMMAND_ANSWER_LEN = 2;
|
static const uint8_t SINGLE_COMMAND_ANSWER_LEN = 2;
|
||||||
|
|
||||||
uint32_t transitionDelay;
|
uint32_t transitionDelay;
|
||||||
//Single SPIcommand has 2 bytes, first for adress, second for content
|
// Single SPI command has 2 bytes, first for adress, second for content
|
||||||
size_t singleComandSize = 2;
|
size_t singleComandSize = 2;
|
||||||
//has the size for all adresses of the lis3mdl + the continous write bit
|
// Has the size for all adresses of the lis3mdl + the continous write bit
|
||||||
uint8_t commandBuffer[MGMLIS3MDL::NR_OF_DATA_AND_CFG_REGISTERS + 1];
|
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
|
* We want to save the registers we set, so we dont have to read the
|
||||||
* registers when we want to change something.
|
* registers when we want to change something.
|
||||||
|
@@ -8,10 +8,9 @@
|
|||||||
|
|
||||||
|
|
||||||
MgmRM3100Handler::MgmRM3100Handler(object_id_t objectId,
|
MgmRM3100Handler::MgmRM3100Handler(object_id_t objectId,
|
||||||
object_id_t deviceCommunication, CookieIF* comCookie, uint8_t switchId,
|
object_id_t deviceCommunication, CookieIF* comCookie, uint32_t transitionDelay):
|
||||||
uint32_t transitionDelay):
|
|
||||||
DeviceHandlerBase(objectId, deviceCommunication, comCookie),
|
DeviceHandlerBase(objectId, deviceCommunication, comCookie),
|
||||||
primaryDataset(this), switchId(switchId), transitionDelay(transitionDelay) {
|
primaryDataset(this), transitionDelay(transitionDelay) {
|
||||||
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
|
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
|
||||||
debugDivider = new PeriodicOperationDivider(3);
|
debugDivider = new PeriodicOperationDivider(3);
|
||||||
#endif
|
#endif
|
||||||
@@ -90,9 +89,16 @@ ReturnValue_t MgmRM3100Handler::buildTransitionDeviceCommand(
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
default:
|
default:
|
||||||
|
#if FSFW_VERBOSE_LEVEL >= 1
|
||||||
|
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||||
// Might be a configuration error
|
// Might be a configuration error
|
||||||
sif::warning << "MgmRM3100Handler::buildTransitionDeviceCommand: Unknown internal state!" <<
|
sif::warning << "MgmRM3100Handler::buildTransitionDeviceCommand: "
|
||||||
std::endl;
|
"Unknown internal state" << std::endl;
|
||||||
|
#else
|
||||||
|
sif::printWarning("MgmRM3100Handler::buildTransitionDeviceCommand: "
|
||||||
|
"Unknown internal state\n");
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -322,13 +328,7 @@ ReturnValue_t MgmRM3100Handler::initializeLocalDataPool(
|
|||||||
}
|
}
|
||||||
|
|
||||||
uint32_t MgmRM3100Handler::getTransitionDelayMs(Mode_t from, Mode_t to) {
|
uint32_t MgmRM3100Handler::getTransitionDelayMs(Mode_t from, Mode_t to) {
|
||||||
return 25000;
|
return this->transitionDelay;
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t MgmRM3100Handler::getSwitches(const uint8_t **switches, uint8_t *numberOfSwitches) {
|
|
||||||
*switches = &switchId;
|
|
||||||
*numberOfSwitches = 1;
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void MgmRM3100Handler::setToGoToNormalMode(bool enable) {
|
void MgmRM3100Handler::setToGoToNormalMode(bool enable) {
|
||||||
@@ -349,12 +349,18 @@ ReturnValue_t MgmRM3100Handler::handleDataReadout(const uint8_t *packet) {
|
|||||||
|
|
||||||
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
|
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
|
||||||
if(debugDivider->checkAndIncrement()) {
|
if(debugDivider->checkAndIncrement()) {
|
||||||
|
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||||
sif::info << "MgmRM3100Handler: Magnetic field strength in"
|
sif::info << "MgmRM3100Handler: Magnetic field strength in"
|
||||||
" microtesla:" << std::endl;
|
" microtesla:" << std::endl;
|
||||||
/* Set terminal to utf-8 if there is an issue with micro printout. */
|
|
||||||
sif::info << "X: " << fieldStrengthX << " uT" << std::endl;
|
sif::info << "X: " << fieldStrengthX << " uT" << std::endl;
|
||||||
sif::info << "Y: " << fieldStrengthY << " uT" << std::endl;
|
sif::info << "Y: " << fieldStrengthY << " uT" << std::endl;
|
||||||
sif::info << "Z: " << fieldStrengthZ << " 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
|
#endif
|
||||||
|
|
||||||
|
@@ -2,7 +2,6 @@
|
|||||||
#define MISSION_DEVICES_MGMRM3100HANDLER_H_
|
#define MISSION_DEVICES_MGMRM3100HANDLER_H_
|
||||||
|
|
||||||
#include "fsfw/FSFW.h"
|
#include "fsfw/FSFW.h"
|
||||||
#include "devices/powerSwitcherList.h"
|
|
||||||
#include "devicedefinitions/MgmRM3100HandlerDefs.h"
|
#include "devicedefinitions/MgmRM3100HandlerDefs.h"
|
||||||
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
||||||
|
|
||||||
@@ -32,7 +31,7 @@ public:
|
|||||||
SUBSYSTEM_ID::MGM_RM3100, 0x01, severity::INFO);
|
SUBSYSTEM_ID::MGM_RM3100, 0x01, severity::INFO);
|
||||||
|
|
||||||
MgmRM3100Handler(object_id_t objectId, object_id_t deviceCommunication,
|
MgmRM3100Handler(object_id_t objectId, object_id_t deviceCommunication,
|
||||||
CookieIF* comCookie, uint8_t switchId, uint32_t transitionDelay = 10000);
|
CookieIF* comCookie, uint32_t transitionDelay);
|
||||||
virtual ~MgmRM3100Handler();
|
virtual ~MgmRM3100Handler();
|
||||||
|
|
||||||
/**
|
/**
|
||||||
@@ -48,21 +47,16 @@ protected:
|
|||||||
DeviceCommandId_t *id) override;
|
DeviceCommandId_t *id) override;
|
||||||
void doStartUp() override;
|
void doStartUp() override;
|
||||||
void doShutDown() override;
|
void doShutDown() override;
|
||||||
ReturnValue_t buildNormalDeviceCommand(
|
ReturnValue_t buildNormalDeviceCommand(DeviceCommandId_t *id) override;
|
||||||
DeviceCommandId_t *id) override;
|
ReturnValue_t buildCommandFromCommand(DeviceCommandId_t deviceCommand,
|
||||||
ReturnValue_t buildCommandFromCommand(
|
const uint8_t *commandData, size_t commandDataLen) override;
|
||||||
DeviceCommandId_t deviceCommand, const uint8_t *commandData,
|
|
||||||
size_t commandDataLen) override;
|
|
||||||
ReturnValue_t scanForReply(const uint8_t *start, size_t len,
|
ReturnValue_t scanForReply(const uint8_t *start, size_t len,
|
||||||
DeviceCommandId_t *foundId, size_t *foundLen) override;
|
DeviceCommandId_t *foundId, size_t *foundLen) override;
|
||||||
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id,
|
ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) override;
|
||||||
const uint8_t *packet) override;
|
|
||||||
ReturnValue_t getSwitches(const uint8_t **switches,
|
|
||||||
uint8_t *numberOfSwitches) override;
|
|
||||||
|
|
||||||
void fillCommandAndReplyMap() override;
|
void fillCommandAndReplyMap() override;
|
||||||
void modeChanged(void) override;
|
void modeChanged(void) 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,
|
ReturnValue_t initializeLocalDataPool(localpool::DataPool &localDataPoolMap,
|
||||||
LocalDataPoolManager &poolManager) override;
|
LocalDataPoolManager &poolManager) override;
|
||||||
|
|
||||||
@@ -97,7 +91,6 @@ private:
|
|||||||
float scaleFactorZ = 1.0 / RM3100::DEFAULT_GAIN;
|
float scaleFactorZ = 1.0 / RM3100::DEFAULT_GAIN;
|
||||||
|
|
||||||
bool goToNormalModeAtStartup = false;
|
bool goToNormalModeAtStartup = false;
|
||||||
uint8_t switchId;
|
|
||||||
uint32_t transitionDelay;
|
uint32_t transitionDelay;
|
||||||
|
|
||||||
ReturnValue_t handleCycleCountConfigCommand(DeviceCommandId_t deviceCommand,
|
ReturnValue_t handleCycleCountConfigCommand(DeviceCommandId_t deviceCommand,
|
||||||
|
@@ -154,7 +154,7 @@ enum MgmPoolIds: lp_id_t {
|
|||||||
TEMPERATURE_CELCIUS
|
TEMPERATURE_CELCIUS
|
||||||
};
|
};
|
||||||
|
|
||||||
class MgmPrimaryDataset: public StaticLocalDataSet<5> {
|
class MgmPrimaryDataset: public StaticLocalDataSet<4> {
|
||||||
public:
|
public:
|
||||||
MgmPrimaryDataset(HasLocalDataPoolIF* hkOwner):
|
MgmPrimaryDataset(HasLocalDataPoolIF* hkOwner):
|
||||||
StaticLocalDataSet(hkOwner, MGM_DATA_SET_ID) {}
|
StaticLocalDataSet(hkOwner, MGM_DATA_SET_ID) {}
|
||||||
|
@@ -49,7 +49,7 @@ static constexpr uint8_t TMRC_DEFAULT_VALUE = TMRC_DEFAULT_37HZ_VALUE;
|
|||||||
|
|
||||||
static constexpr uint8_t MEASUREMENT_REG_START = 0x24;
|
static constexpr uint8_t MEASUREMENT_REG_START = 0x24;
|
||||||
static constexpr uint8_t BIST_REGISTER = 0x33;
|
static constexpr uint8_t BIST_REGISTER = 0x33;
|
||||||
static constexpr uint8_t DATA_READY_VAL = 0b1000'0000;
|
static constexpr uint8_t DATA_READY_VAL = 0b10000000;
|
||||||
static constexpr uint8_t STATUS_REGISTER = 0x34;
|
static constexpr uint8_t STATUS_REGISTER = 0x34;
|
||||||
static constexpr uint8_t REVID_REGISTER = 0x36;
|
static constexpr uint8_t REVID_REGISTER = 0x36;
|
||||||
|
|
||||||
@@ -108,7 +108,7 @@ enum MgmPoolIds: lp_id_t {
|
|||||||
FIELD_STRENGTH_Z,
|
FIELD_STRENGTH_Z,
|
||||||
};
|
};
|
||||||
|
|
||||||
class Rm3100PrimaryDataset: public StaticLocalDataSet<3 * sizeof(float)> {
|
class Rm3100PrimaryDataset: public StaticLocalDataSet<3> {
|
||||||
public:
|
public:
|
||||||
Rm3100PrimaryDataset(HasLocalDataPoolIF* hkOwner):
|
Rm3100PrimaryDataset(HasLocalDataPoolIF* hkOwner):
|
||||||
StaticLocalDataSet(hkOwner, MGM_DATASET_ID) {}
|
StaticLocalDataSet(hkOwner, MGM_DATASET_ID) {}
|
||||||
|
@@ -12,7 +12,7 @@ ReturnValue_t gpio::createRpiGpioConfig(GpioCookie* cookie, gpioId_t gpioId, int
|
|||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
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
|
/* Default chipname for Raspberry Pi. There is still gpiochip1 for expansion, but most users
|
||||||
will not need this */
|
will not need this */
|
||||||
config->chipname = "gpiochip0";
|
config->chipname = "gpiochip0";
|
||||||
|
@@ -141,8 +141,8 @@ ReturnValue_t SpiComIF::sendMessage(CookieIF *cookie, const uint8_t *sendData, s
|
|||||||
if(sendLen > spiCookie->getMaxBufferSize()) {
|
if(sendLen > spiCookie->getMaxBufferSize()) {
|
||||||
#if FSFW_VERBOSE_LEVEL >= 1
|
#if FSFW_VERBOSE_LEVEL >= 1
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||||
sif::warning << "SpiComIF::sendMessage: Too much data sent, send length" << sendLen <<
|
sif::warning << "SpiComIF::sendMessage: Too much data sent, send length " << sendLen <<
|
||||||
"larger than maximum buffer length" << spiCookie->getMaxBufferSize() << std::endl;
|
"larger than maximum buffer length " << spiCookie->getMaxBufferSize() << std::endl;
|
||||||
#else
|
#else
|
||||||
sif::printWarning("SpiComIF::sendMessage: Too much data sent, send length %lu larger "
|
sif::printWarning("SpiComIF::sendMessage: Too much data sent, send length %lu larger "
|
||||||
"than maximum buffer length %lu!\n", static_cast<unsigned long>(sendLen),
|
"than maximum buffer length %lu!\n", static_cast<unsigned long>(sendLen),
|
||||||
@@ -227,7 +227,7 @@ ReturnValue_t SpiComIF::performRegularSendOperation(SpiCookie *spiCookie, const
|
|||||||
utility::handleIoctlError("SpiComIF::sendMessage: ioctl error.");
|
utility::handleIoctlError("SpiComIF::sendMessage: ioctl error.");
|
||||||
result = FULL_DUPLEX_TRANSFER_FAILED;
|
result = FULL_DUPLEX_TRANSFER_FAILED;
|
||||||
}
|
}
|
||||||
#if FSFW_HAL_LINUX_SPI_WIRETAPPING == 1
|
#if FSFW_HAL_SPI_WIRETAPPING == 1
|
||||||
performSpiWiretapping(spiCookie);
|
performSpiWiretapping(spiCookie);
|
||||||
#endif /* FSFW_LINUX_SPI_WIRETAPPING == 1 */
|
#endif /* FSFW_LINUX_SPI_WIRETAPPING == 1 */
|
||||||
}
|
}
|
||||||
@@ -398,11 +398,11 @@ GpioIF* SpiComIF::getGpioInterface() {
|
|||||||
void SpiComIF::setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed) {
|
void SpiComIF::setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed) {
|
||||||
int retval = ioctl(spiFd, SPI_IOC_WR_MODE, reinterpret_cast<uint8_t*>(&mode));
|
int retval = ioctl(spiFd, SPI_IOC_WR_MODE, reinterpret_cast<uint8_t*>(&mode));
|
||||||
if(retval != 0) {
|
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);
|
retval = ioctl(spiFd, SPI_IOC_WR_MAX_SPEED_HZ, &speed);
|
||||||
if(retval != 0) {
|
if(retval != 0) {
|
||||||
utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI speed failed!");
|
utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Setting SPI speed failed");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@@ -16,13 +16,9 @@
|
|||||||
#cmakedefine FSFW_ADD_MONITORING
|
#cmakedefine FSFW_ADD_MONITORING
|
||||||
#cmakedefine FSFW_ADD_SGP4_PROPAGATOR
|
#cmakedefine FSFW_ADD_SGP4_PROPAGATOR
|
||||||
|
|
||||||
#ifndef FSFW_TCP_RECV_WIRETAPPING_ENABLED
|
// Can be used for low-level debugging of the SPI bus
|
||||||
#define FSFW_TCP_RECV_WIRETAPPING_ENABLED 0
|
#ifndef FSFW_HAL_SPI_WIRETAPPING
|
||||||
#endif
|
#define FSFW_HAL_SPI_WIRETAPPING 0
|
||||||
|
|
||||||
/* 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
|
#endif
|
||||||
|
|
||||||
#ifndef FSFW_HAL_L3GD20_GYRO_DEBUG
|
#ifndef FSFW_HAL_L3GD20_GYRO_DEBUG
|
||||||
|
@@ -3,8 +3,8 @@
|
|||||||
|
|
||||||
const char* const FSFW_VERSION_NAME = "ASTP";
|
const char* const FSFW_VERSION_NAME = "ASTP";
|
||||||
|
|
||||||
#define FSFW_VERSION 1
|
#define FSFW_VERSION 2
|
||||||
#define FSFW_SUBVERSION 2
|
#define FSFW_SUBVERSION 0
|
||||||
#define FSFW_REVISION 0
|
#define FSFW_REVISION 0
|
||||||
|
|
||||||
#endif /* FSFW_VERSION_H_ */
|
#endif /* FSFW_VERSION_H_ */
|
||||||
|
@@ -85,10 +85,9 @@ public:
|
|||||||
* Called by DHB in the GET_WRITE doGetWrite().
|
* Called by DHB in the GET_WRITE doGetWrite().
|
||||||
* Get send confirmation that the data in sendMessage() was sent successfully.
|
* Get send confirmation that the data in sendMessage() was sent successfully.
|
||||||
* @param cookie
|
* @param cookie
|
||||||
* @return
|
* @return - @c RETURN_OK if data was sent successfull
|
||||||
* - @c RETURN_OK if data was sent successfully but a reply is expected
|
* - Everything else triggers falure event with
|
||||||
* - NO_REPLY_EXPECTED if data was sent successfully and no reply is expected
|
* returnvalue as parameter 1
|
||||||
* - Everything else to indicate failure
|
|
||||||
*/
|
*/
|
||||||
virtual ReturnValue_t getSendSuccess(CookieIF *cookie) = 0;
|
virtual ReturnValue_t getSendSuccess(CookieIF *cookie) = 0;
|
||||||
|
|
||||||
|
@@ -120,8 +120,7 @@ public:
|
|||||||
static const ReturnValue_t WRONG_MODE_FOR_COMMAND = MAKE_RETURN_CODE(0xA5);
|
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 TIMEOUT = MAKE_RETURN_CODE(0xA6);
|
||||||
static const ReturnValue_t BUSY = MAKE_RETURN_CODE(0xA7);
|
static const ReturnValue_t BUSY = MAKE_RETURN_CODE(0xA7);
|
||||||
//!< Used to indicate that this is a command-only command.
|
static const ReturnValue_t NO_REPLY_EXPECTED = MAKE_RETURN_CODE(0xA8); //!< 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 NON_OP_TEMPERATURE = MAKE_RETURN_CODE(0xA9);
|
||||||
static const ReturnValue_t COMMAND_NOT_IMPLEMENTED = MAKE_RETURN_CODE(0xAA);
|
static const ReturnValue_t COMMAND_NOT_IMPLEMENTED = MAKE_RETURN_CODE(0xAA);
|
||||||
|
|
||||||
|
@@ -29,6 +29,8 @@ enum: uint8_t {
|
|||||||
PUS_SERVICE_9 = 89,
|
PUS_SERVICE_9 = 89,
|
||||||
PUS_SERVICE_17 = 97,
|
PUS_SERVICE_17 = 97,
|
||||||
PUS_SERVICE_23 = 103,
|
PUS_SERVICE_23 = 103,
|
||||||
|
MGM_LIS3MDL = 106,
|
||||||
|
MGM_RM3100 = 107,
|
||||||
|
|
||||||
FW_SUBSYSTEM_ID_RANGE
|
FW_SUBSYSTEM_ID_RANGE
|
||||||
};
|
};
|
||||||
|
@@ -165,11 +165,9 @@ ReturnValue_t DleEncoder::decodeStreamEscaped(const uint8_t *sourceStream, size_
|
|||||||
if (sourceStream[encodedIndex++] != STX_CHAR) {
|
if (sourceStream[encodedIndex++] != STX_CHAR) {
|
||||||
return DECODING_ERROR;
|
return DECODING_ERROR;
|
||||||
}
|
}
|
||||||
while ((encodedIndex < sourceStreamLen)
|
while ((encodedIndex < sourceStreamLen) and (decodedIndex < maxDestStreamlen)) {
|
||||||
and (decodedIndex < maxDestStreamlen)
|
switch(sourceStream[encodedIndex]) {
|
||||||
and (sourceStream[encodedIndex] != ETX_CHAR)
|
case(DLE_CHAR): {
|
||||||
and (sourceStream[encodedIndex] != STX_CHAR)) {
|
|
||||||
if (sourceStream[encodedIndex] == DLE_CHAR) {
|
|
||||||
if(encodedIndex + 1 >= sourceStreamLen) {
|
if(encodedIndex + 1 >= sourceStreamLen) {
|
||||||
//reached the end of the sourceStream
|
//reached the end of the sourceStream
|
||||||
*readLen = sourceStreamLen;
|
*readLen = sourceStreamLen;
|
||||||
@@ -197,30 +195,34 @@ ReturnValue_t DleEncoder::decodeStreamEscaped(const uint8_t *sourceStream, size_
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
++encodedIndex;
|
++encodedIndex;
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
else {
|
case(STX_CHAR): {
|
||||||
|
*readLen = encodedIndex;
|
||||||
|
return DECODING_ERROR;
|
||||||
|
}
|
||||||
|
case(ETX_CHAR): {
|
||||||
|
*readLen = ++encodedIndex;
|
||||||
|
*decodedLen = decodedIndex;
|
||||||
|
return RETURN_OK;
|
||||||
|
}
|
||||||
|
default: {
|
||||||
destStream[decodedIndex] = sourceStream[encodedIndex];
|
destStream[decodedIndex] = sourceStream[encodedIndex];
|
||||||
|
break;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
++encodedIndex;
|
++encodedIndex;
|
||||||
++decodedIndex;
|
++decodedIndex;
|
||||||
}
|
}
|
||||||
if (sourceStream[encodedIndex] != ETX_CHAR) {
|
|
||||||
if(decodedIndex == maxDestStreamlen) {
|
if(decodedIndex == maxDestStreamlen) {
|
||||||
//so far we did not find anything wrong here, so let user try again
|
//so far we did not find anything wrong here, so let user try again
|
||||||
*readLen = 0;
|
*readLen = 0;
|
||||||
return STREAM_TOO_SHORT;
|
return STREAM_TOO_SHORT;
|
||||||
}
|
} else {
|
||||||
else {
|
*readLen = encodedIndex;
|
||||||
*readLen = ++encodedIndex;
|
|
||||||
return DECODING_ERROR;
|
return DECODING_ERROR;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
else {
|
|
||||||
*readLen = ++encodedIndex;
|
|
||||||
*decodedLen = decodedIndex;
|
|
||||||
return RETURN_OK;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t DleEncoder::decodeStreamNonEscaped(const uint8_t *sourceStream,
|
ReturnValue_t DleEncoder::decodeStreamNonEscaped(const uint8_t *sourceStream,
|
||||||
|
@@ -10,11 +10,11 @@ bool PeriodicOperationDivider::checkAndIncrement() {
|
|||||||
bool opNecessary = check();
|
bool opNecessary = check();
|
||||||
if(opNecessary) {
|
if(opNecessary) {
|
||||||
if(resetAutomatically) {
|
if(resetAutomatically) {
|
||||||
counter = 1;
|
counter = 0;
|
||||||
}
|
}
|
||||||
return opNecessary;
|
return opNecessary;
|
||||||
}
|
}
|
||||||
counter++;
|
counter ++;
|
||||||
return opNecessary;
|
return opNecessary;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@@ -81,7 +81,7 @@ public:
|
|||||||
* @param args Any other arguments which an implementation might require
|
* @param args Any other arguments which an implementation might require
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
virtual ReturnValue_t removeFile(const char* repositoryPath,
|
virtual ReturnValue_t deleteFile(const char* repositoryPath,
|
||||||
const char* filename, void* args = nullptr) = 0;
|
const char* filename, void* args = nullptr) = 0;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@@ -1,10 +1,8 @@
|
|||||||
|
#include "fsfw/osal/common/TcpTmTcServer.h"
|
||||||
|
#include "fsfw/osal/common/TcpTmTcBridge.h"
|
||||||
|
#include "fsfw/osal/common/tcpipHelpers.h"
|
||||||
|
|
||||||
#include "fsfw/platform.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/container/SharedRingBuffer.h"
|
||||||
#include "fsfw/ipc/MessageQueueSenderIF.h"
|
#include "fsfw/ipc/MessageQueueSenderIF.h"
|
||||||
#include "fsfw/ipc/MutexGuard.h"
|
#include "fsfw/ipc/MutexGuard.h"
|
||||||
|
@@ -13,10 +13,8 @@ target_sources(${LIB_FSFW_NAME}
|
|||||||
QueueFactory.cpp
|
QueueFactory.cpp
|
||||||
SemaphoreFactory.cpp
|
SemaphoreFactory.cpp
|
||||||
TaskFactory.cpp
|
TaskFactory.cpp
|
||||||
Timer.cpp
|
|
||||||
tcpipHelpers.cpp
|
tcpipHelpers.cpp
|
||||||
unixUtility.cpp
|
unixUtility.cpp
|
||||||
CommandExecutor.cpp
|
|
||||||
)
|
)
|
||||||
|
|
||||||
find_package(Threads REQUIRED)
|
find_package(Threads REQUIRED)
|
||||||
|
@@ -1,185 +0,0 @@
|
|||||||
#include "CommandExecutor.h"
|
|
||||||
|
|
||||||
#include "fsfw/serviceinterface.h"
|
|
||||||
#include "fsfw/container/SimpleRingBuffer.h"
|
|
||||||
#include "fsfw/container/DynamicFIFO.h"
|
|
||||||
|
|
||||||
#include <unistd.h>
|
|
||||||
|
|
||||||
#include <cstring>
|
|
||||||
|
|
||||||
CommandExecutor::CommandExecutor(const size_t maxSize):
|
|
||||||
readVec(maxSize) {
|
|
||||||
waiter.events = POLLIN;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t CommandExecutor::load(std::string command, bool blocking, bool printOutput) {
|
|
||||||
if(state == States::PENDING) {
|
|
||||||
return COMMAND_PENDING;
|
|
||||||
}
|
|
||||||
|
|
||||||
currentCmd = command;
|
|
||||||
this->blocking = blocking;
|
|
||||||
this->printOutput = printOutput;
|
|
||||||
if(state == States::IDLE) {
|
|
||||||
state = States::COMMAND_LOADED;
|
|
||||||
}
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t CommandExecutor::execute() {
|
|
||||||
if(state == States::IDLE) {
|
|
||||||
return NO_COMMAND_LOADED_OR_PENDING;
|
|
||||||
}
|
|
||||||
else if(state == States::PENDING) {
|
|
||||||
return COMMAND_PENDING;
|
|
||||||
}
|
|
||||||
currentCmdFile = popen(currentCmd.c_str(), "r");
|
|
||||||
if(currentCmdFile == nullptr) {
|
|
||||||
lastError = errno;
|
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
|
||||||
}
|
|
||||||
if(blocking) {
|
|
||||||
return executeBlocking();
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
currentFd = fileno(currentCmdFile);
|
|
||||||
waiter.fd = currentFd;
|
|
||||||
}
|
|
||||||
state = States::PENDING;
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t CommandExecutor::close() {
|
|
||||||
if(state == States::PENDING) {
|
|
||||||
// Attempt to close process, irrespective of if it is running or not
|
|
||||||
if(currentCmdFile != nullptr) {
|
|
||||||
pclose(currentCmdFile);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
void CommandExecutor::printLastError(std::string funcName) const {
|
|
||||||
if(lastError != 0) {
|
|
||||||
sif::error << funcName << " pclose failed with code " <<
|
|
||||||
lastError << ": " << strerror(lastError) << std::endl;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void CommandExecutor::setRingBuffer(SimpleRingBuffer *ringBuffer,
|
|
||||||
DynamicFIFO<uint16_t>* sizesFifo) {
|
|
||||||
this->ringBuffer = ringBuffer;
|
|
||||||
this->sizesFifo = sizesFifo;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t CommandExecutor::check(bool& bytesRead) {
|
|
||||||
if(blocking) {
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
}
|
|
||||||
switch(state) {
|
|
||||||
case(States::IDLE):
|
|
||||||
case(States::COMMAND_LOADED): {
|
|
||||||
return NO_COMMAND_LOADED_OR_PENDING;
|
|
||||||
}
|
|
||||||
case(States::PENDING): {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
int result = poll(&waiter, 1, 0);
|
|
||||||
switch(result) {
|
|
||||||
case(0): {
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
case(1): {
|
|
||||||
if (waiter.revents & POLLIN) {
|
|
||||||
ssize_t readBytes = read(currentFd, readVec.data(), readVec.size());
|
|
||||||
if(readBytes == 0) {
|
|
||||||
// Should not happen
|
|
||||||
sif::warning << "CommandExecutor::check: "
|
|
||||||
"No bytes read after poll event.." << std::endl;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
else if(readBytes > 0) {
|
|
||||||
bytesRead = true;
|
|
||||||
if(printOutput) {
|
|
||||||
// It is assumed the command output is line terminated
|
|
||||||
sif::info << currentCmd << " | " << readVec.data();
|
|
||||||
}
|
|
||||||
if(ringBuffer != nullptr) {
|
|
||||||
ringBuffer->writeData(reinterpret_cast<const uint8_t*>(
|
|
||||||
readVec.data()), readBytes);
|
|
||||||
}
|
|
||||||
if(sizesFifo != nullptr) {
|
|
||||||
if(not sizesFifo->full()) {
|
|
||||||
sizesFifo->insert(readBytes);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return BYTES_READ;
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
// Should also not happen
|
|
||||||
sif::warning << "CommandExecutor::check: Error " << errno << ": " <<
|
|
||||||
strerror(errno) << std::endl;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else if(waiter.revents & POLLERR) {
|
|
||||||
sif::warning << "CommandExecuter::check: Poll error" << std::endl;
|
|
||||||
return COMMAND_ERROR;
|
|
||||||
}
|
|
||||||
else if(waiter.revents & POLLHUP) {
|
|
||||||
int result = pclose(currentCmdFile);
|
|
||||||
if(result != 0) {
|
|
||||||
lastError = result;
|
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
|
||||||
}
|
|
||||||
state = States::IDLE;
|
|
||||||
currentCmdFile = nullptr;
|
|
||||||
currentFd = 0;
|
|
||||||
return EXECUTION_FINISHED;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
void CommandExecutor::reset() {
|
|
||||||
CommandExecutor::close();
|
|
||||||
currentCmdFile = nullptr;
|
|
||||||
currentFd = 0;
|
|
||||||
state = States::IDLE;
|
|
||||||
}
|
|
||||||
|
|
||||||
int CommandExecutor::getLastError() const {
|
|
||||||
return this->lastError;
|
|
||||||
}
|
|
||||||
|
|
||||||
CommandExecutor::States CommandExecutor::getCurrentState() const {
|
|
||||||
return state;
|
|
||||||
}
|
|
||||||
|
|
||||||
ReturnValue_t CommandExecutor::executeBlocking() {
|
|
||||||
while(fgets(readVec.data(), readVec.size(), currentCmdFile) != nullptr) {
|
|
||||||
std::string output(readVec.data());
|
|
||||||
if(printOutput) {
|
|
||||||
sif::info << currentCmd << " | " << output;
|
|
||||||
}
|
|
||||||
if(ringBuffer != nullptr) {
|
|
||||||
ringBuffer->writeData(reinterpret_cast<const uint8_t*>(output.data()), output.size());
|
|
||||||
}
|
|
||||||
if(sizesFifo != nullptr) {
|
|
||||||
if(not sizesFifo->full()) {
|
|
||||||
sizesFifo->insert(output.size());
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
int result = pclose(currentCmdFile);
|
|
||||||
if(result != 0) {
|
|
||||||
lastError = result;
|
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
|
||||||
}
|
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
|
||||||
}
|
|
@@ -1,134 +0,0 @@
|
|||||||
#ifndef FSFW_SRC_FSFW_OSAL_LINUX_COMMANDEXECUTOR_H_
|
|
||||||
#define FSFW_SRC_FSFW_OSAL_LINUX_COMMANDEXECUTOR_H_
|
|
||||||
|
|
||||||
#include "fsfw/returnvalues/HasReturnvaluesIF.h"
|
|
||||||
#include "fsfw/returnvalues/FwClassIds.h"
|
|
||||||
|
|
||||||
#include <poll.h>
|
|
||||||
|
|
||||||
#include <string>
|
|
||||||
#include <vector>
|
|
||||||
|
|
||||||
class SimpleRingBuffer;
|
|
||||||
template <typename T> class DynamicFIFO;
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Helper class to execute shell commands in blocking and non-blocking mode
|
|
||||||
* @details
|
|
||||||
* This class is able to execute processes by using the Linux popen call. It also has the
|
|
||||||
* capability of writing the read output of a process into a provided ring buffer.
|
|
||||||
*
|
|
||||||
* The executor works by first loading the command which should be executed and specifying
|
|
||||||
* whether it should be executed blocking or non-blocking. After that, execution can be started
|
|
||||||
* with the execute command. In blocking mode, the execute command will block until the command
|
|
||||||
* has finished
|
|
||||||
*/
|
|
||||||
class CommandExecutor {
|
|
||||||
public:
|
|
||||||
enum class States {
|
|
||||||
IDLE,
|
|
||||||
COMMAND_LOADED,
|
|
||||||
PENDING
|
|
||||||
};
|
|
||||||
|
|
||||||
static constexpr uint8_t CLASS_ID = CLASS_ID::LINUX_OSAL;
|
|
||||||
|
|
||||||
//! [EXPORT] : [COMMENT] Execution of the current command has finished
|
|
||||||
static constexpr ReturnValue_t EXECUTION_FINISHED =
|
|
||||||
HasReturnvaluesIF::makeReturnCode(CLASS_ID, 0);
|
|
||||||
|
|
||||||
//! [EXPORT] : [COMMENT] Command is pending. This will also be returned if the user tries
|
|
||||||
//! to load another command but a command is still pending
|
|
||||||
static constexpr ReturnValue_t COMMAND_PENDING =
|
|
||||||
HasReturnvaluesIF::makeReturnCode(CLASS_ID, 1);
|
|
||||||
//! [EXPORT] : [COMMENT] Some bytes have been read from the executing process
|
|
||||||
static constexpr ReturnValue_t BYTES_READ =
|
|
||||||
HasReturnvaluesIF::makeReturnCode(CLASS_ID, 2);
|
|
||||||
//! [EXPORT] : [COMMENT] Command execution failed
|
|
||||||
static constexpr ReturnValue_t COMMAND_ERROR =
|
|
||||||
HasReturnvaluesIF::makeReturnCode(CLASS_ID, 3);
|
|
||||||
//! [EXPORT] : [COMMENT]
|
|
||||||
static constexpr ReturnValue_t NO_COMMAND_LOADED_OR_PENDING =
|
|
||||||
HasReturnvaluesIF::makeReturnCode(CLASS_ID, 4);
|
|
||||||
static constexpr ReturnValue_t PCLOSE_CALL_ERROR =
|
|
||||||
HasReturnvaluesIF::makeReturnCode(CLASS_ID, 6);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Constructor. Is initialized with maximum size of internal buffer to read data from the
|
|
||||||
* executed process.
|
|
||||||
* @param maxSize
|
|
||||||
*/
|
|
||||||
CommandExecutor(const size_t maxSize);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Load a new command which should be executed
|
|
||||||
* @param command
|
|
||||||
* @param blocking
|
|
||||||
* @param printOutput
|
|
||||||
* @return
|
|
||||||
*/
|
|
||||||
ReturnValue_t load(std::string command, bool blocking, bool printOutput = true);
|
|
||||||
/**
|
|
||||||
* Execute the loaded command.
|
|
||||||
* @return
|
|
||||||
* - In blocking mode, it will return RETURN_FAILED if
|
|
||||||
* the result of the system call was not 0. The error value can be accessed using
|
|
||||||
* getLastError
|
|
||||||
* - In non-blocking mode, this call will start
|
|
||||||
* the execution and then return RETURN_OK
|
|
||||||
*/
|
|
||||||
ReturnValue_t execute();
|
|
||||||
/**
|
|
||||||
* Only used in non-blocking mode. Checks the currently running command.
|
|
||||||
* @param bytesRead Will be set to the number of bytes read, if bytes have been read
|
|
||||||
* @return
|
|
||||||
* - BYTES_READ if bytes have been read from the executing process. It is recommended to call
|
|
||||||
* check again after this
|
|
||||||
* - RETURN_OK execution is pending, but no bytes have been read from the executing process
|
|
||||||
* - RETURN_FAILED if execution has failed, error value can be accessed using getLastError
|
|
||||||
* - EXECUTION_FINISHED if the process was executed successfully
|
|
||||||
* - COMMAND_ERROR internal poll error
|
|
||||||
*/
|
|
||||||
ReturnValue_t check(bool& bytesRead);
|
|
||||||
/**
|
|
||||||
* Abort the current command. Should normally not be necessary, check can be used to find
|
|
||||||
* out whether command execution was successful
|
|
||||||
* @return RETURN_OK
|
|
||||||
*/
|
|
||||||
ReturnValue_t close();
|
|
||||||
|
|
||||||
States getCurrentState() const;
|
|
||||||
int getLastError() const;
|
|
||||||
void printLastError(std::string funcName) const;
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Assign a ring buffer and a FIFO which will be filled by the executor with the output
|
|
||||||
* read from the started process
|
|
||||||
* @param ringBuffer
|
|
||||||
* @param sizesFifo
|
|
||||||
*/
|
|
||||||
void setRingBuffer(SimpleRingBuffer* ringBuffer, DynamicFIFO<uint16_t>* sizesFifo);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Reset the executor. This calls close internally and then reset the state machine so new
|
|
||||||
* commands can be loaded and executed
|
|
||||||
*/
|
|
||||||
void reset();
|
|
||||||
private:
|
|
||||||
std::string currentCmd;
|
|
||||||
bool blocking = true;
|
|
||||||
FILE* currentCmdFile = nullptr;
|
|
||||||
int currentFd = 0;
|
|
||||||
bool printOutput = true;
|
|
||||||
std::vector<char> readVec;
|
|
||||||
struct pollfd waiter {};
|
|
||||||
SimpleRingBuffer* ringBuffer = nullptr;
|
|
||||||
DynamicFIFO<uint16_t>* sizesFifo = nullptr;
|
|
||||||
|
|
||||||
States state = States::IDLE;
|
|
||||||
int lastError = 0;
|
|
||||||
|
|
||||||
ReturnValue_t executeBlocking();
|
|
||||||
};
|
|
||||||
|
|
||||||
#endif /* FSFW_SRC_FSFW_OSAL_LINUX_COMMANDEXECUTOR_H_ */
|
|
@@ -285,10 +285,10 @@ ReturnValue_t MessageQueue::sendMessageFromMessageQueue(MessageQueueId_t sendTo,
|
|||||||
|
|
||||||
utility::printUnixErrorGeneric(CLASS_NAME, "sendMessageFromMessageQueue", "EBADF");
|
utility::printUnixErrorGeneric(CLASS_NAME, "sendMessageFromMessageQueue", "EBADF");
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||||
sif::warning << "mq_send to " << sendTo << " sent from "
|
sif::warning << "mq_send to: " << sendTo << " sent from "
|
||||||
<< sentFrom << " failed" << std::endl;
|
<< sentFrom << "failed" << std::endl;
|
||||||
#else
|
#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
|
#endif
|
||||||
return DESTINATION_INVALID;
|
return DESTINATION_INVALID;
|
||||||
}
|
}
|
||||||
|
@@ -1,57 +0,0 @@
|
|||||||
#include "fsfw/osal/linux/Timer.h"
|
|
||||||
#include "fsfw/serviceinterface/ServiceInterfaceStream.h"
|
|
||||||
#include <errno.h>
|
|
||||||
|
|
||||||
|
|
||||||
Timer::Timer() {
|
|
||||||
sigevent sigEvent;
|
|
||||||
sigEvent.sigev_notify = SIGEV_NONE;
|
|
||||||
sigEvent.sigev_signo = 0;
|
|
||||||
sigEvent.sigev_value.sival_ptr = &timerId;
|
|
||||||
int status = timer_create(CLOCK_MONOTONIC, &sigEvent, &timerId);
|
|
||||||
if(status!=0){
|
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
|
||||||
sif::error << "Timer creation failed with: " << status <<
|
|
||||||
" errno: " << errno << std::endl;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
Timer::~Timer() {
|
|
||||||
timer_delete(timerId);
|
|
||||||
}
|
|
||||||
|
|
||||||
int Timer::setTimer(uint32_t intervalMs) {
|
|
||||||
itimerspec timer;
|
|
||||||
timer.it_value.tv_sec = intervalMs / 1000;
|
|
||||||
timer.it_value.tv_nsec = (intervalMs * 1000000) % (1000000000);
|
|
||||||
timer.it_interval.tv_sec = 0;
|
|
||||||
timer.it_interval.tv_nsec = 0;
|
|
||||||
set = true;
|
|
||||||
return timer_settime(timerId, 0, &timer, NULL);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
int Timer::getTimer(uint32_t* remainingTimeMs){
|
|
||||||
itimerspec timer;
|
|
||||||
timer.it_value.tv_sec = 0;
|
|
||||||
timer.it_value.tv_nsec = 0;
|
|
||||||
timer.it_interval.tv_sec = 0;
|
|
||||||
timer.it_interval.tv_nsec = 0;
|
|
||||||
int status = timer_gettime(timerId, &timer);
|
|
||||||
|
|
||||||
*remainingTimeMs = timer.it_value.tv_sec * 1000 + timer.it_value.tv_nsec / 1000000;
|
|
||||||
|
|
||||||
return status;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool Timer::isSet() const {
|
|
||||||
return this->set;
|
|
||||||
}
|
|
||||||
|
|
||||||
void Timer::resetTimer() {
|
|
||||||
if(not this->set) {
|
|
||||||
set = false;
|
|
||||||
}
|
|
||||||
setTimer(0);
|
|
||||||
}
|
|
@@ -1,49 +0,0 @@
|
|||||||
#ifndef FRAMEWORK_OSAL_LINUX_TIMER_H_
|
|
||||||
#define FRAMEWORK_OSAL_LINUX_TIMER_H_
|
|
||||||
|
|
||||||
#include <signal.h>
|
|
||||||
#include <time.h>
|
|
||||||
#include <stdint.h>
|
|
||||||
|
|
||||||
/**
|
|
||||||
* This class is a helper for the creation of a Clock Monotonic timer which does not trigger a signal
|
|
||||||
*/
|
|
||||||
class Timer {
|
|
||||||
public:
|
|
||||||
/**
|
|
||||||
* Creates the Timer sets the timerId Member
|
|
||||||
*/
|
|
||||||
Timer();
|
|
||||||
/**
|
|
||||||
* Deletes the timer
|
|
||||||
*
|
|
||||||
* Careful! According to POSIX documentation:
|
|
||||||
* The treatment of any pending signal generated by the deleted timer is unspecified.
|
|
||||||
*/
|
|
||||||
virtual ~Timer();
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Set the timer given in timerId to the given interval
|
|
||||||
*
|
|
||||||
* @param intervalMs Interval in ms to be set
|
|
||||||
* @return 0 on Success 1 else
|
|
||||||
*/
|
|
||||||
int setTimer(uint32_t intervalMs);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Get the remaining time of the timer
|
|
||||||
*
|
|
||||||
* @param remainingTimeMs Pointer to integer value which is used to return the remaining time
|
|
||||||
* @return 0 on Success 1 else (see timer_getime documentation of posix function)
|
|
||||||
*/
|
|
||||||
int getTimer(uint32_t* remainingTimeMs);
|
|
||||||
|
|
||||||
bool isSet() const;
|
|
||||||
void resetTimer();
|
|
||||||
|
|
||||||
private:
|
|
||||||
bool set = true;
|
|
||||||
timer_t timerId;
|
|
||||||
};
|
|
||||||
|
|
||||||
#endif /* FRAMEWORK_OSAL_LINUX_TIMER_H_ */
|
|
@@ -41,7 +41,8 @@ ReturnValue_t Service5EventReporting::performService() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||||
sif::warning << "Service5EventReporting::generateEventReport: Too many events" << std::endl;
|
sif::debug << "Service5EventReporting::generateEventReport:"
|
||||||
|
" Too many events" << std::endl;
|
||||||
#endif
|
#endif
|
||||||
return HasReturnvaluesIF::RETURN_OK;
|
return HasReturnvaluesIF::RETURN_OK;
|
||||||
}
|
}
|
||||||
@@ -63,11 +64,8 @@ ReturnValue_t Service5EventReporting::generateEventReport(
|
|||||||
requestQueue->getDefaultDestination(),requestQueue->getId());
|
requestQueue->getDefaultDestination(),requestQueue->getId());
|
||||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
if(result != HasReturnvaluesIF::RETURN_OK) {
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||||
sif::warning << "Service5EventReporting::generateEventReport: "
|
sif::debug << "Service5EventReporting::generateEventReport:"
|
||||||
"Could not send TM packet" << std::endl;
|
" Could not send TM packet" << std::endl;
|
||||||
#else
|
|
||||||
sif::printWarning("Service5EventReporting::generateEventReport: "
|
|
||||||
"Could not send TM packet\n");
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
|
@@ -33,8 +33,8 @@ ReturnValue_t Service8FunctionManagement::getMessageQueueAndObject(
|
|||||||
if(tcDataLen < sizeof(object_id_t)) {
|
if(tcDataLen < sizeof(object_id_t)) {
|
||||||
return CommandingServiceBase::INVALID_TC;
|
return CommandingServiceBase::INVALID_TC;
|
||||||
}
|
}
|
||||||
// Can't fail, size was checked before
|
SerializeAdapter::deSerialize(objectId, &tcData,
|
||||||
SerializeAdapter::deSerialize(objectId, &tcData, &tcDataLen, SerializeIF::Endianness::BIG);
|
&tcDataLen, SerializeIF::Endianness::BIG);
|
||||||
|
|
||||||
return checkInterfaceAndAcquireMessageQueue(id,objectId);
|
return checkInterfaceAndAcquireMessageQueue(id,objectId);
|
||||||
}
|
}
|
||||||
|
@@ -77,6 +77,9 @@ enum: uint8_t {
|
|||||||
HAL_UART, //HURT
|
HAL_UART, //HURT
|
||||||
HAL_I2C, //HI2C
|
HAL_I2C, //HI2C
|
||||||
HAL_GPIO, //HGIO
|
HAL_GPIO, //HGIO
|
||||||
|
FIXED_SLOT_TASK_IF, //FTIF
|
||||||
|
MGM_LIS3MDL, //MGMLIS3
|
||||||
|
MGM_RM3100, //MGMRM3100
|
||||||
FW_CLASS_ID_COUNT // [EXPORT] : [END]
|
FW_CLASS_ID_COUNT // [EXPORT] : [END]
|
||||||
|
|
||||||
};
|
};
|
||||||
|
@@ -22,9 +22,9 @@ public:
|
|||||||
* @param number
|
* @param number
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
static constexpr ReturnValue_t makeReturnCode(uint8_t classId,
|
static constexpr ReturnValue_t makeReturnCode(uint8_t interfaceId,
|
||||||
uint8_t number) {
|
uint8_t number) {
|
||||||
return (static_cast<ReturnValue_t>(classId) << 8) + number;
|
return (static_cast<ReturnValue_t>(interfaceId) << 8) + number;
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@@ -1,4 +1,5 @@
|
|||||||
#include "fsfw/tasks/FixedSlotSequence.h"
|
#include "fsfw/tasks/FixedSlotSequence.h"
|
||||||
|
#include "fsfw/tasks/FixedTimeslotTaskIF.h"
|
||||||
#include "fsfw/serviceinterface/ServiceInterface.h"
|
#include "fsfw/serviceinterface/ServiceInterface.h"
|
||||||
#include <cstdlib>
|
#include <cstdlib>
|
||||||
|
|
||||||
@@ -92,10 +93,9 @@ void FixedSlotSequence::addSlot(object_id_t componentId, uint32_t slotTimeMs,
|
|||||||
ReturnValue_t FixedSlotSequence::checkSequence() const {
|
ReturnValue_t FixedSlotSequence::checkSequence() const {
|
||||||
if(slotList.empty()) {
|
if(slotList.empty()) {
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||||
sif::error << "FixedSlotSequence::checkSequence:"
|
sif::warning << "FixedSlotSequence::checkSequence: Slot list is empty!" << std::endl;
|
||||||
<< " Slot list is empty!" << std::endl;
|
|
||||||
#endif
|
#endif
|
||||||
return HasReturnvaluesIF::RETURN_FAILED;
|
return FixedTimeslotTaskIF::SLOT_LIST_EMPTY;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(customCheckFunction != nullptr) {
|
if(customCheckFunction != nullptr) {
|
||||||
|
@@ -2,7 +2,7 @@
|
|||||||
#define FSFW_TASKS_FIXEDSLOTSEQUENCE_H_
|
#define FSFW_TASKS_FIXEDSLOTSEQUENCE_H_
|
||||||
|
|
||||||
#include "FixedSequenceSlot.h"
|
#include "FixedSequenceSlot.h"
|
||||||
#include "../objectmanager/SystemObject.h"
|
#include "fsfw/objectmanager/SystemObject.h"
|
||||||
|
|
||||||
#include <set>
|
#include <set>
|
||||||
|
|
||||||
@@ -136,6 +136,7 @@ public:
|
|||||||
* @details
|
* @details
|
||||||
* Checks if timing is ok (must be ascending) and if all handlers were found.
|
* Checks if timing is ok (must be ascending) and if all handlers were found.
|
||||||
* @return
|
* @return
|
||||||
|
* - SLOT_LIST_EMPTY if the slot list is empty
|
||||||
*/
|
*/
|
||||||
ReturnValue_t checkSequence() const;
|
ReturnValue_t checkSequence() const;
|
||||||
|
|
||||||
@@ -147,6 +148,7 @@ public:
|
|||||||
* The general check will be continued for now if the custom check function
|
* The general check will be continued for now if the custom check function
|
||||||
* fails but a diagnostic debug output will be given.
|
* fails but a diagnostic debug output will be given.
|
||||||
* @param customCheckFunction
|
* @param customCheckFunction
|
||||||
|
*
|
||||||
*/
|
*/
|
||||||
void addCustomCheck(ReturnValue_t (*customCheckFunction)(const SlotList &));
|
void addCustomCheck(ReturnValue_t (*customCheckFunction)(const SlotList &));
|
||||||
|
|
||||||
|
@@ -2,7 +2,8 @@
|
|||||||
#define FRAMEWORK_TASKS_FIXEDTIMESLOTTASKIF_H_
|
#define FRAMEWORK_TASKS_FIXEDTIMESLOTTASKIF_H_
|
||||||
|
|
||||||
#include "PeriodicTaskIF.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.
|
* @brief Following the same principle as the base class IF.
|
||||||
@@ -12,6 +13,8 @@ class FixedTimeslotTaskIF : public PeriodicTaskIF {
|
|||||||
public:
|
public:
|
||||||
virtual ~FixedTimeslotTaskIF() {}
|
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.
|
* 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
|
* The execution step will be passed to the object (e.g. as an operation
|
||||||
|
@@ -6,16 +6,14 @@ Countdown::Countdown(uint32_t initialTimeout): timeout(initialTimeout) {
|
|||||||
Countdown::~Countdown() {
|
Countdown::~Countdown() {
|
||||||
}
|
}
|
||||||
|
|
||||||
ReturnValue_t Countdown::setTimeout(uint32_t miliseconds) {
|
ReturnValue_t Countdown::setTimeout(uint32_t milliseconds) {
|
||||||
ReturnValue_t return_value = Clock::getUptime( &startTime );
|
ReturnValue_t returnValue = Clock::getUptime( &startTime );
|
||||||
timeout = miliseconds;
|
timeout = milliseconds;
|
||||||
return return_value;
|
return returnValue;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool Countdown::hasTimedOut() const {
|
bool Countdown::hasTimedOut() const {
|
||||||
uint32_t current_time;
|
if ( uint32_t( this->getCurrentTime() - startTime) >= timeout) {
|
||||||
Clock::getUptime( ¤t_time );
|
|
||||||
if ( uint32_t(current_time - startTime) >= timeout) {
|
|
||||||
return true;
|
return true;
|
||||||
} else {
|
} else {
|
||||||
return false;
|
return false;
|
||||||
@@ -31,7 +29,23 @@ ReturnValue_t Countdown::resetTimer() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void Countdown::timeOut() {
|
void Countdown::timeOut() {
|
||||||
uint32_t current_time;
|
startTime = this->getCurrentTime() - timeout;
|
||||||
Clock::getUptime( ¤t_time );
|
}
|
||||||
startTime= current_time - timeout;
|
|
||||||
|
uint32_t Countdown::getRemainingMillis() const {
|
||||||
|
// We fetch the time before the if-statement
|
||||||
|
// to be sure that the return is in
|
||||||
|
// range 0 <= number <= timeout
|
||||||
|
uint32_t currentTime = this->getCurrentTime();
|
||||||
|
if (this->hasTimedOut()){
|
||||||
|
return 0;
|
||||||
|
}else{
|
||||||
|
return (startTime + timeout) - currentTime;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t Countdown::getCurrentTime() const {
|
||||||
|
uint32_t currentTime;
|
||||||
|
Clock::getUptime( ¤tTime );
|
||||||
|
return currentTime;
|
||||||
}
|
}
|
||||||
|
@@ -4,28 +4,77 @@
|
|||||||
#include "Clock.h"
|
#include "Clock.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* @brief This file defines the Countdown class.
|
*
|
||||||
* @author baetz
|
* Countdown keeps track of a timespan.
|
||||||
|
*
|
||||||
|
* Countdown::resetTimer restarts the timer.
|
||||||
|
* Countdown::setTimeout sets a new countdown duration and resets.
|
||||||
|
*
|
||||||
|
* Can be checked with Countdown::hasTimedOut or
|
||||||
|
* Countdown::isBusy.
|
||||||
|
*
|
||||||
|
* Countdown::timeOut will force the timer to time out.
|
||||||
|
*
|
||||||
*/
|
*/
|
||||||
class Countdown {
|
class Countdown {
|
||||||
public:
|
public:
|
||||||
uint32_t timeout;
|
/**
|
||||||
|
* Constructor which sets the countdown duration in milliseconds
|
||||||
|
*
|
||||||
|
* It does not start the countdown!
|
||||||
|
* Call resetTimer or setTimeout before usage!
|
||||||
|
* Otherwise a call to hasTimedOut might return True.
|
||||||
|
*
|
||||||
|
* @param initialTimeout Countdown duration in milliseconds
|
||||||
|
*/
|
||||||
Countdown(uint32_t initialTimeout = 0);
|
Countdown(uint32_t initialTimeout = 0);
|
||||||
~Countdown();
|
~Countdown();
|
||||||
ReturnValue_t setTimeout(uint32_t miliseconds);
|
/**
|
||||||
|
* Call to set a new countdown duration.
|
||||||
|
*
|
||||||
|
* Resets the countdown!
|
||||||
|
*
|
||||||
|
* @param milliseconds new countdown duration in milliseconds
|
||||||
|
* @return Returnvalue from Clock::getUptime
|
||||||
|
*/
|
||||||
|
ReturnValue_t setTimeout(uint32_t milliseconds);
|
||||||
|
/**
|
||||||
|
* Returns true if the countdown duration has passed.
|
||||||
|
*
|
||||||
|
* @return True if the countdown has passed
|
||||||
|
* False if it is still running
|
||||||
|
*/
|
||||||
bool hasTimedOut() const;
|
bool hasTimedOut() const;
|
||||||
|
/**
|
||||||
|
* Complementary to hasTimedOut.
|
||||||
|
*
|
||||||
|
* @return True if the countdown is till running
|
||||||
|
* False if it is still running
|
||||||
|
*/
|
||||||
bool isBusy() const;
|
bool isBusy() const;
|
||||||
|
/**
|
||||||
//!< Use last set timeout value and restart timer.
|
* Uses last set timeout value and restarts timer.
|
||||||
|
*/
|
||||||
ReturnValue_t resetTimer();
|
ReturnValue_t resetTimer();
|
||||||
|
/**
|
||||||
//!< Make hasTimedOut() return true
|
* Returns the remaining milliseconds (0 if timeout)
|
||||||
|
*/
|
||||||
|
uint32_t getRemainingMillis() const;
|
||||||
|
/**
|
||||||
|
* Makes hasTimedOut() return true
|
||||||
|
*/
|
||||||
void timeOut();
|
void timeOut();
|
||||||
|
/**
|
||||||
|
* Internal countdown duration in milliseconds
|
||||||
|
*/
|
||||||
|
uint32_t timeout;
|
||||||
private:
|
private:
|
||||||
|
/**
|
||||||
|
* Last time the timer was started (uptime)
|
||||||
|
*/
|
||||||
uint32_t startTime = 0;
|
uint32_t startTime = 0;
|
||||||
|
|
||||||
|
uint32_t getCurrentTime() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* FSFW_TIMEMANAGER_COUNTDOWN_H_ */
|
#endif /* FSFW_TIMEMANAGER_COUNTDOWN_H_ */
|
||||||
|
@@ -19,7 +19,8 @@ public:
|
|||||||
/**
|
/**
|
||||||
* The constructor initializes the packet and sets all header information
|
* The constructor initializes the packet and sets all header information
|
||||||
* according to the passed parameters.
|
* according to the passed parameters.
|
||||||
* @param packetDataLength Sets the packet data length field and therefore specifies the size of the packet.
|
* @param packetDataLength Sets the packet data length field and therefore specifies
|
||||||
|
* the size of the packet.
|
||||||
* @param isTelecommand Sets the packet type field to either TC (true) or TM (false).
|
* @param isTelecommand Sets the packet type field to either TC (true) or TM (false).
|
||||||
* @param apid Sets the packet's APID field. The default value describes an idle packet.
|
* @param apid Sets the packet's APID field. The default value describes an idle packet.
|
||||||
* @param sequenceCount ets the packet's Source Sequence Count field.
|
* @param sequenceCount ets the packet's Source Sequence Count field.
|
||||||
|
@@ -60,8 +60,9 @@ uint16_t SpacePacketBase::getAPID( void ) const {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void SpacePacketBase::setAPID( uint16_t new_apid ) {
|
void SpacePacketBase::setAPID( uint16_t new_apid ) {
|
||||||
//Use first three bits of new APID, but keep rest of packet id as it was (see specification).
|
// Use first three bits of new APID, but keep rest of packet id as it was (see specification).
|
||||||
this->data->header.packet_id_h = (this->data->header.packet_id_h & 0b11111000) | ( ( new_apid & 0x0700 ) >> 8 );
|
this->data->header.packet_id_h = (this->data->header.packet_id_h & 0b11111000) |
|
||||||
|
( ( new_apid & 0x0700 ) >> 8 );
|
||||||
this->data->header.packet_id_l = ( new_apid & 0x00FF );
|
this->data->header.packet_id_l = ( new_apid & 0x00FF );
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -85,7 +86,8 @@ uint16_t SpacePacketBase::getPacketSequenceCount( void ) const {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void SpacePacketBase::setPacketSequenceCount( uint16_t new_count) {
|
void SpacePacketBase::setPacketSequenceCount( uint16_t new_count) {
|
||||||
this->data->header.sequence_control_h = ( this->data->header.sequence_control_h & 0b11000000 ) | ( ( (new_count%LIMIT_SEQUENCE_COUNT) & 0x3F00 ) >> 8 );
|
this->data->header.sequence_control_h = ( this->data->header.sequence_control_h & 0b11000000 ) |
|
||||||
|
( ( (new_count%LIMIT_SEQUENCE_COUNT) & 0x3F00 ) >> 8 );
|
||||||
this->data->header.sequence_control_l = ( (new_count%LIMIT_SEQUENCE_COUNT) & 0x00FF );
|
this->data->header.sequence_control_l = ( (new_count%LIMIT_SEQUENCE_COUNT) & 0x00FF );
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -100,7 +102,7 @@ void SpacePacketBase::setPacketDataLength( uint16_t new_length) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
size_t SpacePacketBase::getFullSize() {
|
size_t SpacePacketBase::getFullSize() {
|
||||||
//+1 is done because size in packet data length field is: size of data field -1
|
// +1 is done because size in packet data length field is: size of data field -1
|
||||||
return this->getPacketDataLength() + sizeof(this->data->header) + 1;
|
return this->getPacketDataLength() + sizeof(this->data->header) + 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@@ -70,7 +70,8 @@ public:
|
|||||||
*/
|
*/
|
||||||
virtual ~SpacePacketBase();
|
virtual ~SpacePacketBase();
|
||||||
|
|
||||||
//CCSDS Methods:
|
//CCSDS Methods
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Getter for the packet version number field.
|
* Getter for the packet version number field.
|
||||||
* @return Returns the highest three bit of the packet in one byte.
|
* @return Returns the highest three bit of the packet in one byte.
|
||||||
@@ -162,7 +163,7 @@ public:
|
|||||||
*/
|
*/
|
||||||
void setPacketDataLength( uint16_t setLength );
|
void setPacketDataLength( uint16_t setLength );
|
||||||
|
|
||||||
//Helper methods:
|
// Helper methods
|
||||||
/**
|
/**
|
||||||
* This method returns a raw uint8_t pointer to the packet.
|
* This method returns a raw uint8_t pointer to the packet.
|
||||||
* @return A \c uint8_t pointer to the first byte of the CCSDS primary header.
|
* @return A \c uint8_t pointer to the first byte of the CCSDS primary header.
|
||||||
|
16
src/fsfw/tmtcpacket/pus/definitions.h
Normal file
16
src/fsfw/tmtcpacket/pus/definitions.h
Normal file
@@ -0,0 +1,16 @@
|
|||||||
|
#ifndef FSFW_SRC_FSFW_TMTCPACKET_PUS_TM_DEFINITIONS_H_
|
||||||
|
#define FSFW_SRC_FSFW_TMTCPACKET_PUS_TM_DEFINITIONS_H_
|
||||||
|
|
||||||
|
#include <cstdint>
|
||||||
|
|
||||||
|
namespace pus {
|
||||||
|
|
||||||
|
//! Version numbers according to ECSS-E-ST-70-41C p.439
|
||||||
|
enum PusVersion: uint8_t {
|
||||||
|
PUS_A_VERSION = 1,
|
||||||
|
PUS_C_VERSION = 2
|
||||||
|
};
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif /* FSFW_SRC_FSFW_TMTCPACKET_PUS_TM_DEFINITIONS_H_ */
|
@@ -1,4 +1,4 @@
|
|||||||
#include "fsfw/tmtcpacket/pus/tc/TcPacketPus.h"
|
#include "TcPacketPus.h"
|
||||||
#include "fsfw/globalfunctions/CRC.h"
|
#include "fsfw/globalfunctions/CRC.h"
|
||||||
|
|
||||||
#include <cstring>
|
#include <cstring>
|
||||||
@@ -8,14 +8,13 @@ TcPacketPus::TcPacketPus(const uint8_t *setData): TcPacketBase(setData) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void TcPacketPus::initializeTcPacket(uint16_t apid, uint16_t sequenceCount,
|
void TcPacketPus::initializeTcPacket(uint16_t apid, uint16_t sequenceCount,
|
||||||
uint8_t ack, uint8_t service, uint8_t subservice, uint16_t sourceId) {
|
uint8_t ack, uint8_t service, uint8_t subservice, pus::PusVersion pusVersion,
|
||||||
|
uint16_t sourceId) {
|
||||||
initSpacePacketHeader(true, true, apid, sequenceCount);
|
initSpacePacketHeader(true, true, apid, sequenceCount);
|
||||||
std::memset(&tcData->dataField, 0, sizeof(tcData->dataField));
|
std::memset(&tcData->dataField, 0, sizeof(tcData->dataField));
|
||||||
setPacketDataLength(sizeof(PUSTcDataFieldHeader) + CRC_SIZE - 1);
|
setPacketDataLength(sizeof(PUSTcDataFieldHeader) + CRC_SIZE - 1);
|
||||||
// Data Field Header:
|
// Data Field Header. For PUS A, the first bit (CCSDS Secondary Header Flag) is zero
|
||||||
// Set CCSDS_secondary_header_flag to 0 and version number to 001
|
tcData->dataField.versionTypeAck = pusVersion << 4 | (ack & 0x0F);
|
||||||
tcData->dataField.versionTypeAck = 0b00010000;
|
|
||||||
tcData->dataField.versionTypeAck |= (ack & 0x0F);
|
|
||||||
tcData->dataField.serviceType = service;
|
tcData->dataField.serviceType = service;
|
||||||
tcData->dataField.serviceSubtype = subservice;
|
tcData->dataField.serviceSubtype = subservice;
|
||||||
#if FSFW_USE_PUS_C_TELECOMMANDS == 1
|
#if FSFW_USE_PUS_C_TELECOMMANDS == 1
|
||||||
|
@@ -2,6 +2,7 @@
|
|||||||
#define FSFW_TMTCPACKET_PUS_TCPACKETPUSA_H_
|
#define FSFW_TMTCPACKET_PUS_TCPACKETPUSA_H_
|
||||||
|
|
||||||
#include "fsfw/FSFW.h"
|
#include "fsfw/FSFW.h"
|
||||||
|
#include "../definitions.h"
|
||||||
#include "fsfw/tmtcpacket/ccsds_header.h"
|
#include "fsfw/tmtcpacket/ccsds_header.h"
|
||||||
#include "TcPacketBase.h"
|
#include "TcPacketBase.h"
|
||||||
|
|
||||||
@@ -75,7 +76,8 @@ protected:
|
|||||||
* @param subservice PUS Subservice
|
* @param subservice PUS Subservice
|
||||||
*/
|
*/
|
||||||
void initializeTcPacket(uint16_t apid, uint16_t sequenceCount, uint8_t ack,
|
void initializeTcPacket(uint16_t apid, uint16_t sequenceCount, uint8_t ack,
|
||||||
uint8_t service, uint8_t subservice, uint16_t sourceId = 0);
|
uint8_t service, uint8_t subservice, pus::PusVersion pusVersion,
|
||||||
|
uint16_t sourceId = 0);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* A pointer to a structure which defines the data structure of
|
* A pointer to a structure which defines the data structure of
|
||||||
|
@@ -23,7 +23,12 @@ TcPacketStoredPus::TcPacketStoredPus(uint16_t apid, uint8_t service,
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
this->setData(pData);
|
this->setData(pData);
|
||||||
initializeTcPacket(apid, sequenceCount, ack, service, subservice);
|
#if FSFW_USE_PUS_C_TELECOMMANDS == 1
|
||||||
|
pus::PusVersion pusVersion = pus::PusVersion::PUS_C_VERSION;
|
||||||
|
#else
|
||||||
|
pus::PusVersion pusVersion = pus::PusVersion::PUS_A_VERSION;
|
||||||
|
#endif
|
||||||
|
initializeTcPacket(apid, sequenceCount, ack, service, subservice, pusVersion);
|
||||||
std::memcpy(&tcData->appData, data, size);
|
std::memcpy(&tcData->appData, data, size);
|
||||||
this->setPacketDataLength(
|
this->setPacketDataLength(
|
||||||
size + sizeof(PUSTcDataFieldHeader) + CRC_SIZE - 1);
|
size + sizeof(PUSTcDataFieldHeader) + CRC_SIZE - 1);
|
||||||
|
@@ -31,8 +31,6 @@ public:
|
|||||||
//! Maximum size of a TM Packet in this mission.
|
//! Maximum size of a TM Packet in this mission.
|
||||||
//! TODO: Make this dependant on a config variable.
|
//! TODO: Make this dependant on a config variable.
|
||||||
static const uint32_t MISSION_TM_PACKET_MAX_SIZE = 2048;
|
static const uint32_t MISSION_TM_PACKET_MAX_SIZE = 2048;
|
||||||
//! First four bits of first byte of secondary header
|
|
||||||
static const uint8_t VERSION_NUMBER_BYTE = 0b00010000;
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* This is the default constructor.
|
* This is the default constructor.
|
||||||
|
@@ -1,5 +1,6 @@
|
|||||||
#include "fsfw/tmtcpacket/pus/tm/TmPacketPusA.h"
|
#include "../definitions.h"
|
||||||
#include "fsfw/tmtcpacket/pus/tm/TmPacketBase.h"
|
#include "TmPacketPusA.h"
|
||||||
|
#include "TmPacketBase.h"
|
||||||
|
|
||||||
#include "fsfw/globalfunctions/CRC.h"
|
#include "fsfw/globalfunctions/CRC.h"
|
||||||
#include "fsfw/globalfunctions/arrayprinter.h"
|
#include "fsfw/globalfunctions/arrayprinter.h"
|
||||||
@@ -62,12 +63,7 @@ void TmPacketPusA::initializeTmPacket(uint16_t apid, uint8_t service,
|
|||||||
//First, set to zero.
|
//First, set to zero.
|
||||||
memset(&tmData->data_field, 0, sizeof(tmData->data_field));
|
memset(&tmData->data_field, 0, sizeof(tmData->data_field));
|
||||||
|
|
||||||
// NOTE: In PUS-C, the PUS Version is 2 and specified for the first 4 bits.
|
tmData->data_field.version_type_ack = pus::PusVersion::PUS_A_VERSION << 4;
|
||||||
// The other 4 bits of the first byte are the spacecraft time reference
|
|
||||||
// status. To change to PUS-C, set 0b00100000.
|
|
||||||
// Set CCSDS_secondary header flag to 0, version number to 001 and ack
|
|
||||||
// to 0000
|
|
||||||
tmData->data_field.version_type_ack = 0b00010000;
|
|
||||||
tmData->data_field.service_type = service;
|
tmData->data_field.service_type = service;
|
||||||
tmData->data_field.service_subtype = subservice;
|
tmData->data_field.service_subtype = subservice;
|
||||||
tmData->data_field.subcounter = packetSubcounter;
|
tmData->data_field.subcounter = packetSubcounter;
|
||||||
|
@@ -1,5 +1,6 @@
|
|||||||
#include "fsfw/tmtcpacket/pus/tm/TmPacketPusC.h"
|
#include "../definitions.h"
|
||||||
#include "fsfw/tmtcpacket/pus/tm/TmPacketBase.h"
|
#include "TmPacketPusC.h"
|
||||||
|
#include "TmPacketBase.h"
|
||||||
|
|
||||||
#include "fsfw/globalfunctions/CRC.h"
|
#include "fsfw/globalfunctions/CRC.h"
|
||||||
#include "fsfw/globalfunctions/arrayprinter.h"
|
#include "fsfw/globalfunctions/arrayprinter.h"
|
||||||
@@ -67,7 +68,8 @@ ReturnValue_t TmPacketPusC::initializeTmPacket(uint16_t apid, uint8_t service,
|
|||||||
|
|
||||||
/* Only account for last 4 bytes for time reference field */
|
/* Only account for last 4 bytes for time reference field */
|
||||||
timeRefField &= 0b1111;
|
timeRefField &= 0b1111;
|
||||||
tmData->dataField.versionTimeReferenceField = VERSION_NUMBER_BYTE | timeRefField;
|
tmData->dataField.versionTimeReferenceField =
|
||||||
|
(pus::PusVersion::PUS_C_VERSION << 4) | timeRefField;
|
||||||
tmData->dataField.serviceType = service;
|
tmData->dataField.serviceType = service;
|
||||||
tmData->dataField.serviceSubtype = subservice;
|
tmData->dataField.serviceSubtype = subservice;
|
||||||
tmData->dataField.subcounterMsb = packetSubcounter << 8 & 0xff;
|
tmData->dataField.subcounterMsb = packetSubcounter << 8 & 0xff;
|
||||||
|
@@ -91,4 +91,34 @@ void TmPacketStoredBase::checkAndReportLostTm() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void TmPacketStoredBase::handleStoreFailure(const char *const packetType, ReturnValue_t result,
|
||||||
|
size_t sizeToReserve) {
|
||||||
|
checkAndReportLostTm();
|
||||||
|
#if FSFW_VERBOSE_LEVEL >= 1
|
||||||
|
switch(result) {
|
||||||
|
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||||
|
case(StorageManagerIF::DATA_STORAGE_FULL): {
|
||||||
|
sif::warning << "TmPacketStoredPus" << packetType << ": " <<
|
||||||
|
"Store full for packet with size" << sizeToReserve << std::endl;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case(StorageManagerIF::DATA_TOO_LARGE): {
|
||||||
|
sif::warning << "TmPacketStoredPus" << packetType << ": Data with size " <<
|
||||||
|
sizeToReserve << " too large" << std::endl;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
case(StorageManagerIF::DATA_STORAGE_FULL): {
|
||||||
|
sif::printWarning("TmPacketStoredPus%s: Store full for packet with "
|
||||||
|
"size %d\n", packetType, sizeToReserve);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case(StorageManagerIF::DATA_TOO_LARGE): {
|
||||||
|
sif::printWarning("TmPacketStoredPus%s: Data with size "
|
||||||
|
"%d too large\n", packetType, sizeToReserve);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
@@ -82,6 +82,9 @@ protected:
|
|||||||
bool checkAndSetStore();
|
bool checkAndSetStore();
|
||||||
|
|
||||||
void checkAndReportLostTm();
|
void checkAndReportLostTm();
|
||||||
|
|
||||||
|
void handleStoreFailure(const char* const packetType, ReturnValue_t result,
|
||||||
|
size_t sizeToReserve);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
@@ -5,32 +5,32 @@
|
|||||||
|
|
||||||
#include <cstring>
|
#include <cstring>
|
||||||
|
|
||||||
TmPacketStoredPusA::TmPacketStoredPusA(store_address_t setAddress) :
|
TmPacketStoredPusA::TmPacketStoredPusA(store_address_t setAddress):
|
||||||
TmPacketStoredBase(setAddress), TmPacketPusA(nullptr){
|
TmPacketStoredBase(setAddress), TmPacketPusA(nullptr){
|
||||||
}
|
}
|
||||||
|
|
||||||
TmPacketStoredPusA::TmPacketStoredPusA(uint16_t apid, uint8_t service,
|
TmPacketStoredPusA::TmPacketStoredPusA(uint16_t apid, uint8_t service,
|
||||||
uint8_t subservice, uint8_t packetSubcounter, const uint8_t *data,
|
uint8_t subservice, uint8_t packetSubcounter, const uint8_t *data,
|
||||||
uint32_t size, const uint8_t *headerData, uint32_t headerSize) :
|
uint32_t size, const uint8_t *headerData, uint32_t headerSize):
|
||||||
TmPacketPusA(nullptr) {
|
TmPacketPusA(nullptr) {
|
||||||
storeAddress.raw = StorageManagerIF::INVALID_ADDRESS;
|
storeAddress.raw = StorageManagerIF::INVALID_ADDRESS;
|
||||||
if (not TmPacketStoredBase::checkAndSetStore()) {
|
if (not TmPacketStoredBase::checkAndSetStore()) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
uint8_t *pData = nullptr;
|
uint8_t *pData = nullptr;
|
||||||
|
size_t sizeToReserve = getPacketMinimumSize() + size + headerSize;
|
||||||
ReturnValue_t returnValue = store->getFreeElement(&storeAddress,
|
ReturnValue_t returnValue = store->getFreeElement(&storeAddress,
|
||||||
(getPacketMinimumSize() + size + headerSize), &pData);
|
sizeToReserve, &pData);
|
||||||
|
|
||||||
if (returnValue != store->RETURN_OK) {
|
if (returnValue != store->RETURN_OK) {
|
||||||
TmPacketStoredBase::checkAndReportLostTm();
|
handleStoreFailure("A", returnValue, sizeToReserve);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
setData(pData);
|
setData(pData);
|
||||||
initializeTmPacket(apid, service, subservice, packetSubcounter);
|
initializeTmPacket(apid, service, subservice, packetSubcounter);
|
||||||
memcpy(getSourceData(), headerData, headerSize);
|
memcpy(getSourceData(), headerData, headerSize);
|
||||||
memcpy(getSourceData() + headerSize, data, size);
|
memcpy(getSourceData() + headerSize, data, size);
|
||||||
setPacketDataLength(
|
setPacketDataLength(size + headerSize + sizeof(PUSTmDataFieldHeaderPusA) + CRC_SIZE - 1);
|
||||||
size + headerSize + sizeof(PUSTmDataFieldHeaderPusA) + CRC_SIZE - 1);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
TmPacketStoredPusA::TmPacketStoredPusA(uint16_t apid, uint8_t service,
|
TmPacketStoredPusA::TmPacketStoredPusA(uint16_t apid, uint8_t service,
|
||||||
@@ -42,32 +42,33 @@ TmPacketStoredPusA::TmPacketStoredPusA(uint16_t apid, uint8_t service,
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
size_t sourceDataSize = 0;
|
size_t sourceDataSize = 0;
|
||||||
if (content != NULL) {
|
if (content != nullptr) {
|
||||||
sourceDataSize += content->getSerializedSize();
|
sourceDataSize += content->getSerializedSize();
|
||||||
}
|
}
|
||||||
if (header != NULL) {
|
if (header != nullptr) {
|
||||||
sourceDataSize += header->getSerializedSize();
|
sourceDataSize += header->getSerializedSize();
|
||||||
}
|
}
|
||||||
uint8_t *p_data = NULL;
|
uint8_t *pData = nullptr;
|
||||||
|
size_t sizeToReserve = getPacketMinimumSize() + sourceDataSize;
|
||||||
ReturnValue_t returnValue = store->getFreeElement(&storeAddress,
|
ReturnValue_t returnValue = store->getFreeElement(&storeAddress,
|
||||||
(getPacketMinimumSize() + sourceDataSize), &p_data);
|
sizeToReserve, &pData);
|
||||||
if (returnValue != store->RETURN_OK) {
|
if (returnValue != store->RETURN_OK) {
|
||||||
TmPacketStoredBase::checkAndReportLostTm();
|
handleStoreFailure("A", returnValue, sizeToReserve);
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
setData(p_data);
|
setData(pData);
|
||||||
initializeTmPacket(apid, service, subservice, packetSubcounter);
|
initializeTmPacket(apid, service, subservice, packetSubcounter);
|
||||||
uint8_t *putDataHere = getSourceData();
|
uint8_t *putDataHere = getSourceData();
|
||||||
size_t size = 0;
|
size_t size = 0;
|
||||||
if (header != NULL) {
|
if (header != nullptr) {
|
||||||
header->serialize(&putDataHere, &size, sourceDataSize,
|
header->serialize(&putDataHere, &size, sourceDataSize,
|
||||||
SerializeIF::Endianness::BIG);
|
SerializeIF::Endianness::BIG);
|
||||||
}
|
}
|
||||||
if (content != NULL) {
|
if (content != nullptr) {
|
||||||
content->serialize(&putDataHere, &size, sourceDataSize,
|
content->serialize(&putDataHere, &size, sourceDataSize,
|
||||||
SerializeIF::Endianness::BIG);
|
SerializeIF::Endianness::BIG);
|
||||||
}
|
}
|
||||||
setPacketDataLength(
|
setPacketDataLength(sourceDataSize + sizeof(PUSTmDataFieldHeaderPusA) + CRC_SIZE - 1);
|
||||||
sourceDataSize + sizeof(PUSTmDataFieldHeaderPusA) + CRC_SIZE - 1);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t* TmPacketStoredPusA::getAllTmData() {
|
uint8_t* TmPacketStoredPusA::getAllTmData() {
|
||||||
|
@@ -15,7 +15,7 @@
|
|||||||
* packets in a store with the help of a storeAddress.
|
* packets in a store with the help of a storeAddress.
|
||||||
* @ingroup tmtcpackets
|
* @ingroup tmtcpackets
|
||||||
*/
|
*/
|
||||||
class TmPacketStoredPusA :
|
class TmPacketStoredPusA:
|
||||||
public TmPacketStoredBase,
|
public TmPacketStoredBase,
|
||||||
public TmPacketPusA {
|
public TmPacketPusA {
|
||||||
public:
|
public:
|
||||||
|
@@ -19,19 +19,19 @@ TmPacketStoredPusC::TmPacketStoredPusC(uint16_t apid, uint8_t service,
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
uint8_t *pData = nullptr;
|
uint8_t *pData = nullptr;
|
||||||
|
size_t sizeToReserve = getPacketMinimumSize() + size + headerSize;
|
||||||
ReturnValue_t returnValue = store->getFreeElement(&storeAddress,
|
ReturnValue_t returnValue = store->getFreeElement(&storeAddress,
|
||||||
(getPacketMinimumSize() + size + headerSize), &pData);
|
sizeToReserve, &pData);
|
||||||
|
|
||||||
if (returnValue != store->RETURN_OK) {
|
if (returnValue != store->RETURN_OK) {
|
||||||
TmPacketStoredBase::checkAndReportLostTm();
|
handleStoreFailure("C", returnValue, sizeToReserve);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
setData(pData);
|
setData(pData);
|
||||||
initializeTmPacket(apid, service, subservice, packetSubcounter, destinationId, timeRefField);
|
initializeTmPacket(apid, service, subservice, packetSubcounter, destinationId, timeRefField);
|
||||||
memcpy(getSourceData(), headerData, headerSize);
|
memcpy(getSourceData(), headerData, headerSize);
|
||||||
memcpy(getSourceData() + headerSize, data, size);
|
memcpy(getSourceData() + headerSize, data, size);
|
||||||
setPacketDataLength(
|
setPacketDataLength(size + headerSize + sizeof(PUSTmDataFieldHeaderPusC) + CRC_SIZE - 1);
|
||||||
size + headerSize + sizeof(PUSTmDataFieldHeaderPusC) + CRC_SIZE - 1);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
TmPacketStoredPusC::TmPacketStoredPusC(uint16_t apid, uint8_t service,
|
TmPacketStoredPusC::TmPacketStoredPusC(uint16_t apid, uint8_t service,
|
||||||
@@ -53,34 +53,7 @@ TmPacketStoredPusC::TmPacketStoredPusC(uint16_t apid, uint8_t service,
|
|||||||
size_t sizeToReserve = getPacketMinimumSize() + sourceDataSize;
|
size_t sizeToReserve = getPacketMinimumSize() + sourceDataSize;
|
||||||
ReturnValue_t returnValue = store->getFreeElement(&storeAddress, sizeToReserve, &pData);
|
ReturnValue_t returnValue = store->getFreeElement(&storeAddress, sizeToReserve, &pData);
|
||||||
if (returnValue != store->RETURN_OK) {
|
if (returnValue != store->RETURN_OK) {
|
||||||
#if FSFW_VERBOSE_LEVEL >= 1
|
handleStoreFailure("C", returnValue, sizeToReserve);
|
||||||
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;
|
return;
|
||||||
}
|
}
|
||||||
setData(pData);
|
setData(pData);
|
||||||
|
@@ -16,15 +16,18 @@ InternalUnitTester::~InternalUnitTester() {}
|
|||||||
ReturnValue_t InternalUnitTester::performTests(
|
ReturnValue_t InternalUnitTester::performTests(
|
||||||
const struct InternalUnitTester::TestConfig& testConfig) {
|
const struct InternalUnitTester::TestConfig& testConfig) {
|
||||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||||
sif::info << "Running internal unit tests.." << std::endl;
|
sif::info << "Running internal unit tests.. Error messages might follow" <<
|
||||||
|
std::endl;
|
||||||
#else
|
#else
|
||||||
sif::printInfo("Running internal unit tests..\n");
|
sif::printInfo("Running internal unit tests..\n");
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
testserialize::test_serialization();
|
testserialize::test_serialization();
|
||||||
testmq::testMq();
|
testmq::testMq();
|
||||||
|
if(testConfig.testSemaphores) {
|
||||||
testsemaph::testBinSemaph();
|
testsemaph::testBinSemaph();
|
||||||
testsemaph::testCountingSemaph();
|
testsemaph::testCountingSemaph();
|
||||||
|
}
|
||||||
testmutex::testMutex();
|
testmutex::testMutex();
|
||||||
if(testConfig.testArrayPrinter) {
|
if(testConfig.testArrayPrinter) {
|
||||||
arrayprinter::testArrayPrinter();
|
arrayprinter::testArrayPrinter();
|
||||||
|
@@ -18,6 +18,7 @@ class InternalUnitTester: public HasReturnvaluesIF {
|
|||||||
public:
|
public:
|
||||||
struct TestConfig {
|
struct TestConfig {
|
||||||
bool testArrayPrinter = false;
|
bool testArrayPrinter = false;
|
||||||
|
bool testSemaphores = true;
|
||||||
};
|
};
|
||||||
|
|
||||||
InternalUnitTester();
|
InternalUnitTester();
|
||||||
|
@@ -1,10 +1,12 @@
|
|||||||
#include "fsfw_tests/internal/osal/IntTestMutex.h"
|
#include "fsfw_tests/internal/osal/IntTestMutex.h"
|
||||||
#include "fsfw_tests/internal/UnittDefinitions.h"
|
#include "fsfw_tests/internal/UnittDefinitions.h"
|
||||||
|
#include "fsfw/platform.h"
|
||||||
|
|
||||||
#include <fsfw/ipc/MutexFactory.h>
|
#include <fsfw/ipc/MutexFactory.h>
|
||||||
|
|
||||||
#if defined(WIN32) || defined(UNIX)
|
#if defined PLATFORM_WIN || defined PLATFORM_UNIX
|
||||||
#include <fsfw/osal/host/Mutex.h>
|
#include "fsfw/osal/host/Mutex.h"
|
||||||
|
|
||||||
#include <thread>
|
#include <thread>
|
||||||
#include <future>
|
#include <future>
|
||||||
#endif
|
#endif
|
||||||
@@ -20,7 +22,7 @@ void testmutex::testMutex() {
|
|||||||
// timed_mutex from the C++ library specifies undefined behaviour if
|
// timed_mutex from the C++ library specifies undefined behaviour if
|
||||||
// the timed mutex is locked twice from the same thread.
|
// the timed mutex is locked twice from the same thread.
|
||||||
// TODO: we should pass a define like FSFW_OSAL_HOST to the build.
|
// TODO: we should pass a define like FSFW_OSAL_HOST to the build.
|
||||||
#if defined(WIN32) || defined(UNIX)
|
#if defined PLATFORM_WIN || defined PLATFORM_UNIX
|
||||||
// This calls the function from
|
// This calls the function from
|
||||||
// another thread and stores the returnvalue in a future.
|
// another thread and stores the returnvalue in a future.
|
||||||
auto future = std::async(&MutexIF::lockMutex, mutex, MutexIF::TimeoutType::WAITING, 1);
|
auto future = std::async(&MutexIF::lockMutex, mutex, MutexIF::TimeoutType::WAITING, 1);
|
||||||
@@ -37,8 +39,7 @@ void testmutex::testMutex() {
|
|||||||
unitt::put_error(id);
|
unitt::put_error(id);
|
||||||
}
|
}
|
||||||
|
|
||||||
// TODO: we should pass a define like FSFW_OSAL_HOST to the build.
|
#if !defined PLATFORM_WIN && !defined PLATFORM_UNIX
|
||||||
#if !defined(WIN32) && !defined(UNIX)
|
|
||||||
result = mutex->unlockMutex();
|
result = mutex->unlockMutex();
|
||||||
if(result != MutexIF::CURR_THREAD_DOES_NOT_OWN_MUTEX) {
|
if(result != MutexIF::CURR_THREAD_DOES_NOT_OWN_MUTEX) {
|
||||||
unitt::put_error(id);
|
unitt::put_error(id);
|
||||||
|
@@ -1,9 +1,10 @@
|
|||||||
|
#include "fsfw/FSFW.h"
|
||||||
#include "fsfw_tests/internal/osal/IntTestSemaphore.h"
|
#include "fsfw_tests/internal/osal/IntTestSemaphore.h"
|
||||||
#include "fsfw_tests/internal/UnittDefinitions.h"
|
#include "fsfw_tests/internal/UnittDefinitions.h"
|
||||||
|
|
||||||
#include <fsfw/tasks/SemaphoreFactory.h>
|
#include "fsfw/tasks/SemaphoreFactory.h"
|
||||||
#include <fsfw/serviceinterface/ServiceInterface.h>
|
#include "fsfw/serviceinterface/ServiceInterface.h"
|
||||||
#include <fsfw/timemanager/Stopwatch.h>
|
#include "fsfw/timemanager/Stopwatch.h"
|
||||||
|
|
||||||
#include <cstdlib>
|
#include <cstdlib>
|
||||||
|
|
||||||
@@ -16,7 +17,7 @@ void testsemaph::testBinSemaph() {
|
|||||||
}
|
}
|
||||||
testBinSemaphoreImplementation(binSemaph, id);
|
testBinSemaphoreImplementation(binSemaph, id);
|
||||||
SemaphoreFactory::instance()->deleteSemaphore(binSemaph);
|
SemaphoreFactory::instance()->deleteSemaphore(binSemaph);
|
||||||
#if defined(freeRTOS)
|
#if defined FSFW_OSAL_FREERTOS
|
||||||
SemaphoreIF* binSemaphUsingTask =
|
SemaphoreIF* binSemaphUsingTask =
|
||||||
SemaphoreFactory::instance()->createBinarySemaphore(1);
|
SemaphoreFactory::instance()->createBinarySemaphore(1);
|
||||||
testBinSemaphoreImplementation(binSemaphUsingTask, id);
|
testBinSemaphoreImplementation(binSemaphUsingTask, id);
|
||||||
@@ -36,7 +37,7 @@ void testsemaph::testCountingSemaph() {
|
|||||||
}
|
}
|
||||||
testBinSemaphoreImplementation(countingSemaph, id);
|
testBinSemaphoreImplementation(countingSemaph, id);
|
||||||
SemaphoreFactory::instance()->deleteSemaphore(countingSemaph);
|
SemaphoreFactory::instance()->deleteSemaphore(countingSemaph);
|
||||||
#if defined(freeRTOS)
|
#if defined FSFW_OSAL_FREERTOS
|
||||||
countingSemaph = SemaphoreFactory::instance()->
|
countingSemaph = SemaphoreFactory::instance()->
|
||||||
createCountingSemaphore(1, 1, 1);
|
createCountingSemaphore(1, 1, 1);
|
||||||
testBinSemaphoreImplementation(countingSemaph, id);
|
testBinSemaphoreImplementation(countingSemaph, id);
|
||||||
@@ -50,7 +51,7 @@ void testsemaph::testCountingSemaph() {
|
|||||||
createCountingSemaphore(3,3);
|
createCountingSemaphore(3,3);
|
||||||
testCountingSemaphImplementation(countingSemaph, id);
|
testCountingSemaphImplementation(countingSemaph, id);
|
||||||
SemaphoreFactory::instance()->deleteSemaphore(countingSemaph);
|
SemaphoreFactory::instance()->deleteSemaphore(countingSemaph);
|
||||||
#if defined(freeRTOS)
|
#if defined FSFW_OSAL_FREERTOS
|
||||||
countingSemaph = SemaphoreFactory::instance()->
|
countingSemaph = SemaphoreFactory::instance()->
|
||||||
createCountingSemaphore(3, 0, 1);
|
createCountingSemaphore(3, 0, 1);
|
||||||
uint8_t semaphCount = countingSemaph->getSemaphoreCounter();
|
uint8_t semaphCount = countingSemaph->getSemaphoreCounter();
|
||||||
|
@@ -18,4 +18,5 @@ add_subdirectory(serialize)
|
|||||||
add_subdirectory(datapoollocal)
|
add_subdirectory(datapoollocal)
|
||||||
add_subdirectory(storagemanager)
|
add_subdirectory(storagemanager)
|
||||||
add_subdirectory(globalfunctions)
|
add_subdirectory(globalfunctions)
|
||||||
|
add_subdirectory(timemanager)
|
||||||
add_subdirectory(tmtcpacket)
|
add_subdirectory(tmtcpacket)
|
||||||
|
@@ -103,7 +103,7 @@ TEST_CASE("DleEncoder" , "[DleEncoder]") {
|
|||||||
for(size_t faultyDestSize = 0; faultyDestSize < expectedVec.size(); faultyDestSize ++) {
|
for(size_t faultyDestSize = 0; faultyDestSize < expectedVec.size(); faultyDestSize ++) {
|
||||||
result = dleEncoder.encode(vecToEncode.data(), vecToEncode.size(),
|
result = dleEncoder.encode(vecToEncode.data(), vecToEncode.size(),
|
||||||
buffer.data(), faultyDestSize, &encodedLen);
|
buffer.data(), faultyDestSize, &encodedLen);
|
||||||
REQUIRE(result == DleEncoder::STREAM_TOO_SHORT);
|
REQUIRE(result == static_cast<int>(DleEncoder::STREAM_TOO_SHORT));
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
@@ -218,5 +218,10 @@ TEST_CASE("DleEncoder" , "[DleEncoder]") {
|
|||||||
REQUIRE(result == static_cast<int>(DleEncoder::DECODING_ERROR));
|
REQUIRE(result == static_cast<int>(DleEncoder::DECODING_ERROR));
|
||||||
|
|
||||||
dleEncoder.setEscapeMode(true);
|
dleEncoder.setEscapeMode(true);
|
||||||
|
testArray1EncodedFaulty = TEST_ARRAY_1_ENCODED_ESCAPED;
|
||||||
|
testArray1EncodedFaulty[5] = 0;
|
||||||
|
result = dleEncoder.decode(testArray1EncodedFaulty.data(), testArray1EncodedFaulty.size(),
|
||||||
|
&readLen, buffer.data(), buffer.size(), &encodedLen);
|
||||||
|
REQUIRE(result == static_cast<int>(DleEncoder::DECODING_ERROR));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
3
tests/src/fsfw_tests/unit/timemanager/CMakeLists.txt
Normal file
3
tests/src/fsfw_tests/unit/timemanager/CMakeLists.txt
Normal file
@@ -0,0 +1,3 @@
|
|||||||
|
target_sources(${TARGET_NAME} PRIVATE
|
||||||
|
TestCountdown.cpp
|
||||||
|
)
|
27
tests/src/fsfw_tests/unit/timemanager/TestCountdown.cpp
Normal file
27
tests/src/fsfw_tests/unit/timemanager/TestCountdown.cpp
Normal file
@@ -0,0 +1,27 @@
|
|||||||
|
#include "fsfw_tests/unit/CatchDefinitions.h"
|
||||||
|
#include <fsfw/timemanager/Countdown.h>
|
||||||
|
#include <catch2/catch_test_macros.hpp>
|
||||||
|
|
||||||
|
|
||||||
|
TEST_CASE( "Countdown Tests", "[TestCountdown]") {
|
||||||
|
INFO("Countdown Tests");
|
||||||
|
Countdown count(20);
|
||||||
|
REQUIRE(count.timeout == 20);
|
||||||
|
REQUIRE(count.setTimeout(100) == static_cast<uint16_t>(HasReturnvaluesIF::RETURN_OK));
|
||||||
|
REQUIRE(count.timeout == 100);
|
||||||
|
REQUIRE(count.setTimeout(150) == static_cast<uint16_t>(HasReturnvaluesIF::RETURN_OK));
|
||||||
|
REQUIRE(count.isBusy());
|
||||||
|
REQUIRE(not count.hasTimedOut());
|
||||||
|
uint32_t number = count.getRemainingMillis();
|
||||||
|
REQUIRE(number > 0);
|
||||||
|
bool blocked = false;
|
||||||
|
while(not count.hasTimedOut()){
|
||||||
|
blocked = true;
|
||||||
|
};
|
||||||
|
REQUIRE(blocked);
|
||||||
|
number = count.getRemainingMillis();
|
||||||
|
REQUIRE(number==0);
|
||||||
|
count.resetTimer();
|
||||||
|
REQUIRE(not count.hasTimedOut());
|
||||||
|
REQUIRE(count.isBusy());
|
||||||
|
}
|
Reference in New Issue
Block a user