Merge remote-tracking branch 'origin/eive/develop' into mueller/gpio-hal-updates
fsfw/fsfw/pipeline/pr-development This commit looks good Details

This commit is contained in:
Robin Müller 2022-02-28 15:49:11 +01:00
commit ac036b2a70
No known key found for this signature in database
GPG Key ID: 11D4952C8CCEF814
64 changed files with 423 additions and 271 deletions

View File

@ -9,6 +9,7 @@ option(FSFW_HAL_ADD_LINUX "Add the Linux HAL to the sources. Requires gpiod libr
# Linux. The only exception from this is the gpiod library which requires a dedicated installation, # Linux. The only exception from this is the gpiod library which requires a dedicated installation,
# but CMake is able to determine whether this library is installed with find_library. # but CMake is able to determine whether this library is installed with find_library.
option(FSFW_HAL_LINUX_ADD_PERIPHERAL_DRIVERS "Add peripheral drivers for embedded Linux" ON) option(FSFW_HAL_LINUX_ADD_PERIPHERAL_DRIVERS "Add peripheral drivers for embedded Linux" ON)
option(FSFW_HAL_LINUX_ADD_LIBGPIOD "Target implements libgpiod" ON)
option(FSFW_HAL_ADD_RASPBERRY_PI "Add Raspberry Pi specific code to the sources" OFF) option(FSFW_HAL_ADD_RASPBERRY_PI "Add Raspberry Pi specific code to the sources" OFF)
option(FSFW_HAL_ADD_STM32H7 "Add the STM32H7 HAL to the sources" OFF) option(FSFW_HAL_ADD_STM32H7 "Add the STM32H7 HAL to the sources" OFF)

View File

@ -79,8 +79,8 @@ class GpiodRegularBase : public GpioBase {
class GpiodRegularByChip : public GpiodRegularBase { class GpiodRegularByChip : public GpiodRegularBase {
public: public:
GpiodRegularByChip() GpiodRegularByChip()
: GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP, std::string(), : GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP, std::string(), gpio::Direction::IN,
gpio::Direction::IN, gpio::Levels::LOW, 0) {} gpio::Levels::LOW, 0) {}
GpiodRegularByChip(std::string chipname_, int lineNum_, std::string consumer_, GpiodRegularByChip(std::string chipname_, int lineNum_, std::string consumer_,
gpio::Direction direction_, gpio::Levels initValue_) gpio::Direction direction_, gpio::Levels initValue_)
@ -126,8 +126,8 @@ class GpiodRegularByLineName : public GpiodRegularBase {
lineName(lineName_) {} lineName(lineName_) {}
GpiodRegularByLineName(std::string lineName_, std::string consumer_) GpiodRegularByLineName(std::string lineName_, std::string consumer_)
: GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME, consumer_, : GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LINE_NAME, consumer_, gpio::Direction::IN,
gpio::Direction::IN, gpio::Levels::LOW), gpio::Levels::LOW),
lineName(lineName_) {} lineName(lineName_) {}
std::string lineName; std::string lineName;

View File

@ -8,11 +8,7 @@ GyroHandlerL3GD20H::GyroHandlerL3GD20H(object_id_t objectId, object_id_t deviceC
CookieIF *comCookie, uint32_t transitionDelayMs) CookieIF *comCookie, uint32_t transitionDelayMs)
: DeviceHandlerBase(objectId, deviceCommunication, comCookie), : DeviceHandlerBase(objectId, deviceCommunication, comCookie),
transitionDelayMs(transitionDelayMs), transitionDelayMs(transitionDelayMs),
dataset(this) { dataset(this) {}
#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1
debugDivider = new PeriodicOperationDivider(10);
#endif
}
GyroHandlerL3GD20H::~GyroHandlerL3GD20H() {} GyroHandlerL3GD20H::~GyroHandlerL3GD20H() {}
@ -193,22 +189,22 @@ ReturnValue_t GyroHandlerL3GD20H::interpretDeviceReply(DeviceCommandId_t id,
int8_t temperaturOffset = (-1) * packet[L3GD20H::TEMPERATURE_IDX]; int8_t temperaturOffset = (-1) * packet[L3GD20H::TEMPERATURE_IDX];
float temperature = 25.0 + temperaturOffset; float temperature = 25.0 + temperaturOffset;
#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1 if (periodicPrintout) {
if (debugDivider->checkAndIncrement()) { if (debugDivider.checkAndIncrement()) {
/* Set terminal to utf-8 if there is an issue with micro printout. */ /* 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 << "GyroHandlerL3GD20H: Angular velocities (deg/s):" << std::endl; sif::info << "GyroHandlerL3GD20H: Angular velocities (deg/s):" << std::endl;
sif::info << "X: " << angVelocX << std::endl; sif::info << "X: " << angVelocX << std::endl;
sif::info << "Y: " << angVelocY << std::endl; sif::info << "Y: " << angVelocY << std::endl;
sif::info << "Z: " << angVelocZ << std::endl; sif::info << "Z: " << angVelocZ << std::endl;
#else #else
sif::printInfo("GyroHandlerL3GD20H: Angular velocities (deg/s):\n"); sif::printInfo("GyroHandlerL3GD20H: Angular velocities (deg/s):\n");
sif::printInfo("X: %f\n", angVelocX); sif::printInfo("X: %f\n", angVelocX);
sif::printInfo("Y: %f\n", angVelocY); sif::printInfo("Y: %f\n", angVelocY);
sif::printInfo("Z: %f\n", angVelocZ); sif::printInfo("Z: %f\n", angVelocZ);
#endif #endif
}
} }
#endif
PoolReadGuard readSet(&dataset); PoolReadGuard readSet(&dataset);
if (readSet.getReadResult() == HasReturnvaluesIF::RETURN_OK) { if (readSet.getReadResult() == HasReturnvaluesIF::RETURN_OK) {
@ -272,3 +268,8 @@ void GyroHandlerL3GD20H::setAbsoluteLimits(float limitX, float limitY, float lim
this->absLimitY = limitY; this->absLimitY = limitY;
this->absLimitZ = limitZ; this->absLimitZ = limitZ;
} }
void GyroHandlerL3GD20H::enablePeriodicPrintouts(bool enable, uint8_t divider) {
periodicPrintout = enable;
debugDivider.setDivider(divider);
}

View File

@ -5,7 +5,6 @@
#include <fsfw/globalfunctions/PeriodicOperationDivider.h> #include <fsfw/globalfunctions/PeriodicOperationDivider.h>
#include "devicedefinitions/GyroL3GD20Definitions.h" #include "devicedefinitions/GyroL3GD20Definitions.h"
#include "fsfw/FSFW.h"
/** /**
* @brief Device Handler for the L3GD20H gyroscope sensor * @brief Device Handler for the L3GD20H gyroscope sensor
@ -22,6 +21,8 @@ class GyroHandlerL3GD20H : public DeviceHandlerBase {
uint32_t transitionDelayMs); uint32_t transitionDelayMs);
virtual ~GyroHandlerL3GD20H(); virtual ~GyroHandlerL3GD20H();
void enablePeriodicPrintouts(bool enable, uint8_t divider);
/** /**
* Set the absolute limit for the values on the axis in degrees per second. * 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 * The dataset values will be marked as invalid if that limit is exceeded
@ -80,9 +81,8 @@ class GyroHandlerL3GD20H : public DeviceHandlerBase {
// Set default value // Set default value
float sensitivity = L3GD20H::SENSITIVITY_00; float sensitivity = L3GD20H::SENSITIVITY_00;
#if FSFW_HAL_L3GD20_GYRO_DEBUG == 1 bool periodicPrintout = false;
PeriodicOperationDivider *debugDivider = nullptr; PeriodicOperationDivider debugDivider = PeriodicOperationDivider(3);
#endif
}; };
#endif /* MISSION_DEVICES_GYROL3GD20HANDLER_H_ */ #endif /* MISSION_DEVICES_GYROL3GD20HANDLER_H_ */

View File

@ -12,9 +12,6 @@ MgmLIS3MDLHandler::MgmLIS3MDLHandler(object_id_t objectId, object_id_t deviceCom
: DeviceHandlerBase(objectId, deviceCommunication, comCookie), : DeviceHandlerBase(objectId, deviceCommunication, comCookie),
dataset(this), dataset(this),
transitionDelay(transitionDelay) { transitionDelay(transitionDelay) {
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1
debugDivider = new PeriodicOperationDivider(10);
#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;
@ -272,23 +269,24 @@ ReturnValue_t MgmLIS3MDLHandler::interpretDeviceReply(DeviceCommandId_t id, cons
float mgmZ = static_cast<float>(mgmMeasurementRawZ) * sensitivityFactor * float mgmZ = static_cast<float>(mgmMeasurementRawZ) * sensitivityFactor *
MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR; MGMLIS3MDL::GAUSS_TO_MICROTESLA_FACTOR;
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1 if (periodicPrintout) {
if (debugDivider->checkAndIncrement()) { if (debugDivider.checkAndIncrement()) {
#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:" " microtesla:"
<< std::endl; << std::endl;
sif::info << "X: " << mgmX << " uT" << std::endl; sif::info << "X: " << mgmX << " uT" << std::endl;
sif::info << "Y: " << mgmY << " uT" << std::endl; sif::info << "Y: " << mgmY << " uT" << std::endl;
sif::info << "Z: " << mgmZ << " uT" << std::endl; sif::info << "Z: " << mgmZ << " uT" << std::endl;
#else #else
sif::printInfo("MGMHandlerLIS3: Magnetic field strength in microtesla:\n"); sif::printInfo("MGMHandlerLIS3: Magnetic field strength in microtesla:\n");
sif::printInfo("X: %f uT\n", mgmX); sif::printInfo("X: %f uT\n", mgmX);
sif::printInfo("Y: %f uT\n", mgmY); sif::printInfo("Y: %f uT\n", mgmY);
sif::printInfo("Z: %f uT\n", mgmZ); sif::printInfo("Z: %f uT\n", mgmZ);
#endif /* FSFW_CPP_OSTREAM_ENABLED == 0 */ #endif /* FSFW_CPP_OSTREAM_ENABLED == 0 */
}
} }
#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) { if (std::abs(mgmX) < absLimitX) {
@ -318,15 +316,16 @@ ReturnValue_t MgmLIS3MDLHandler::interpretDeviceReply(DeviceCommandId_t id, cons
case MGMLIS3MDL::READ_TEMPERATURE: { case MGMLIS3MDL::READ_TEMPERATURE: {
int16_t tempValueRaw = packet[2] << 8 | packet[1]; int16_t tempValueRaw = packet[2] << 8 | packet[1];
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 (periodicPrintout) {
if (debugDivider->check()) { if (debugDivider.check()) {
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::info << "MGMHandlerLIS3: Temperature: " << tempValue << " C" << std::endl; sif::info << "MGMHandlerLIS3: Temperature: " << tempValue << " C" << std::endl;
#else #else
sif::printInfo("MGMHandlerLIS3: Temperature: %f C\n"); sif::printInfo("MGMHandlerLIS3: Temperature: %f C\n");
#endif #endif
}
} }
#endif
ReturnValue_t result = dataset.read(); ReturnValue_t result = dataset.read();
if (result == HasReturnvaluesIF::RETURN_OK) { if (result == HasReturnvaluesIF::RETURN_OK) {
dataset.temperature = tempValue; dataset.temperature = tempValue;
@ -484,3 +483,8 @@ void MgmLIS3MDLHandler::setAbsoluteLimits(float xLimit, float yLimit, float zLim
this->absLimitY = yLimit; this->absLimitY = yLimit;
this->absLimitZ = zLimit; this->absLimitZ = zLimit;
} }
void MgmLIS3MDLHandler::enablePeriodicPrintouts(bool enable, uint8_t divider) {
periodicPrintout = enable;
debugDivider.setDivider(divider);
}

View File

@ -3,8 +3,8 @@
#include "devicedefinitions/MgmLIS3HandlerDefs.h" #include "devicedefinitions/MgmLIS3HandlerDefs.h"
#include "events/subsystemIdRanges.h" #include "events/subsystemIdRanges.h"
#include "fsfw/FSFW.h"
#include "fsfw/devicehandlers/DeviceHandlerBase.h" #include "fsfw/devicehandlers/DeviceHandlerBase.h"
#include "fsfw/globalfunctions/PeriodicOperationDivider.h"
class PeriodicOperationDivider; class PeriodicOperationDivider;
@ -30,6 +30,7 @@ class MgmLIS3MDLHandler : public DeviceHandlerBase {
uint32_t transitionDelay); uint32_t transitionDelay);
virtual ~MgmLIS3MDLHandler(); virtual ~MgmLIS3MDLHandler();
void enablePeriodicPrintouts(bool enable, uint8_t divider);
/** /**
* Set the absolute limit for the values on the axis in microtesla. The dataset values will * 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 * be marked as invalid if that limit is exceeded
@ -167,9 +168,8 @@ class MgmLIS3MDLHandler : public DeviceHandlerBase {
*/ */
ReturnValue_t prepareCtrlRegisterWrite(); ReturnValue_t prepareCtrlRegisterWrite();
#if FSFW_HAL_LIS3MDL_MGM_DEBUG == 1 bool periodicPrintout = false;
PeriodicOperationDivider *debugDivider; PeriodicOperationDivider debugDivider = PeriodicOperationDivider(3);
#endif
}; };
#endif /* MISSION_DEVICES_MGMLIS3MDLHANDLER_H_ */ #endif /* MISSION_DEVICES_MGMLIS3MDLHANDLER_H_ */

View File

@ -10,11 +10,7 @@ MgmRM3100Handler::MgmRM3100Handler(object_id_t objectId, object_id_t deviceCommu
CookieIF *comCookie, uint32_t transitionDelay) CookieIF *comCookie, uint32_t transitionDelay)
: DeviceHandlerBase(objectId, deviceCommunication, comCookie), : DeviceHandlerBase(objectId, deviceCommunication, comCookie),
primaryDataset(this), primaryDataset(this),
transitionDelay(transitionDelay) { transitionDelay(transitionDelay) {}
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
debugDivider = new PeriodicOperationDivider(10);
#endif
}
MgmRM3100Handler::~MgmRM3100Handler() {} MgmRM3100Handler::~MgmRM3100Handler() {}
@ -337,23 +333,23 @@ ReturnValue_t MgmRM3100Handler::handleDataReadout(const uint8_t *packet) {
float fieldStrengthY = fieldStrengthRawY * scaleFactorX; float fieldStrengthY = fieldStrengthRawY * scaleFactorX;
float fieldStrengthZ = fieldStrengthRawZ * scaleFactorX; float fieldStrengthZ = fieldStrengthRawZ * scaleFactorX;
#if FSFW_HAL_RM3100_MGM_DEBUG == 1 if (periodicPrintout) {
if (debugDivider->checkAndIncrement()) { if (debugDivider.checkAndIncrement()) {
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::info << "MgmRM3100Handler: Magnetic field strength in" sif::info << "MgmRM3100Handler: Magnetic field strength in"
" microtesla:" " microtesla:"
<< std::endl; << std::endl;
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 #else
sif::printInfo("MgmRM3100Handler: Magnetic field strength in microtesla:\n"); sif::printInfo("MgmRM3100Handler: Magnetic field strength in microtesla:\n");
sif::printInfo("X: %f uT\n", fieldStrengthX); sif::printInfo("X: %f uT\n", fieldStrengthX);
sif::printInfo("Y: %f uT\n", fieldStrengthY); sif::printInfo("Y: %f uT\n", fieldStrengthY);
sif::printInfo("Z: %f uT\n", fieldStrengthZ); sif::printInfo("Z: %f uT\n", fieldStrengthZ);
#endif #endif
}
} }
#endif
// TODO: Sanity check on values? // TODO: Sanity check on values?
PoolReadGuard readGuard(&primaryDataset); PoolReadGuard readGuard(&primaryDataset);
@ -365,3 +361,8 @@ ReturnValue_t MgmRM3100Handler::handleDataReadout(const uint8_t *packet) {
} }
return RETURN_OK; return RETURN_OK;
} }
void MgmRM3100Handler::enablePeriodicPrintouts(bool enable, uint8_t divider) {
periodicPrintout = enable;
debugDivider.setDivider(divider);
}

View File

@ -2,12 +2,8 @@
#define MISSION_DEVICES_MGMRM3100HANDLER_H_ #define MISSION_DEVICES_MGMRM3100HANDLER_H_
#include "devicedefinitions/MgmRM3100HandlerDefs.h" #include "devicedefinitions/MgmRM3100HandlerDefs.h"
#include "fsfw/FSFW.h"
#include "fsfw/devicehandlers/DeviceHandlerBase.h" #include "fsfw/devicehandlers/DeviceHandlerBase.h"
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
#include "fsfw/globalfunctions/PeriodicOperationDivider.h" #include "fsfw/globalfunctions/PeriodicOperationDivider.h"
#endif
/** /**
* @brief Device Handler for the RM3100 geomagnetic magnetometer sensor * @brief Device Handler for the RM3100 geomagnetic magnetometer sensor
@ -33,6 +29,7 @@ class MgmRM3100Handler : public DeviceHandlerBase {
uint32_t transitionDelay); uint32_t transitionDelay);
virtual ~MgmRM3100Handler(); virtual ~MgmRM3100Handler();
void enablePeriodicPrintouts(bool enable, uint8_t divider);
/** /**
* Configure device handler to go to normal mode after startup immediately * Configure device handler to go to normal mode after startup immediately
* @param enable * @param enable
@ -98,9 +95,9 @@ class MgmRM3100Handler : public DeviceHandlerBase {
size_t commandDataLen); size_t commandDataLen);
ReturnValue_t handleDataReadout(const uint8_t *packet); ReturnValue_t handleDataReadout(const uint8_t *packet);
#if FSFW_HAL_RM3100_MGM_DEBUG == 1
PeriodicOperationDivider *debugDivider; bool periodicPrintout = false;
#endif PeriodicOperationDivider debugDivider = PeriodicOperationDivider(3);
}; };
#endif /* MISSION_DEVICEHANDLING_MGMRM3100HANDLER_H_ */ #endif /* MISSION_DEVICEHANDLING_MGMRM3100HANDLER_H_ */

View File

@ -9,7 +9,9 @@ target_sources(${LIB_FSFW_NAME} PRIVATE
) )
if(FSFW_HAL_LINUX_ADD_PERIPHERAL_DRIVERS) if(FSFW_HAL_LINUX_ADD_PERIPHERAL_DRIVERS)
if(FSFW_HAL_LINUX_ADD_LIBGPIOD)
add_subdirectory(gpio) add_subdirectory(gpio)
endif()
add_subdirectory(spi) add_subdirectory(spi)
add_subdirectory(i2c) add_subdirectory(i2c)
add_subdirectory(uart) add_subdirectory(uart)

View File

@ -163,7 +163,7 @@ ReturnValue_t LinuxLibgpioIF::configureRegularGpio(gpioId_t gpioId, struct gpiod
switch (direction) { switch (direction) {
case (gpio::Direction::OUT): { case (gpio::Direction::OUT): {
result = gpiod_line_request_output(lineHandle, consumer.c_str(), result = gpiod_line_request_output(lineHandle, consumer.c_str(),
static_cast<int>(regularGpio.initValue)); static_cast<int>(regularGpio.initValue));
break; break;
} }
case (gpio::Direction::IN): { case (gpio::Direction::IN): {

View File

@ -401,4 +401,12 @@ void SpiComIF::setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed)
if (retval != 0) { if (retval != 0) {
utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Setting SPI speed failed"); utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Setting SPI speed failed");
} }
// This updates the SPI clock default polarity. Only setting the mode does not update
// the line state, which can be an issue on mode switches because the clock line will
// switch the state after the chip select is pulled low
clockUpdateTransfer.len = 0;
retval = ioctl(spiFd, SPI_IOC_MESSAGE(1), &clockUpdateTransfer);
if (retval != 0) {
utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Updating SPI default clock failed");
}
} }

View File

@ -74,6 +74,7 @@ class SpiComIF : public DeviceCommunicationIF, public SystemObject {
MutexIF* spiMutex = nullptr; MutexIF* spiMutex = nullptr;
MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING;
uint32_t timeoutMs = 20; uint32_t timeoutMs = 20;
spi_ioc_transfer clockUpdateTransfer = {};
using SpiDeviceMap = std::unordered_map<address_t, SpiInstance>; using SpiDeviceMap = std::unordered_map<address_t, SpiInstance>;
using SpiDeviceMapIter = SpiDeviceMap::iterator; using SpiDeviceMapIter = SpiDeviceMap::iterator;

View File

@ -1,7 +1,4 @@
#include "UartComIF.h" #include "UartComIF.h"
#include "fsfw/FSFW.h"
#include "fsfw/serviceinterface.h"
#include "fsfw_hal/linux/utility.h"
#include <errno.h> #include <errno.h>
#include <fcntl.h> #include <fcntl.h>
@ -10,6 +7,10 @@
#include <cstring> #include <cstring>
#include "fsfw/FSFW.h"
#include "fsfw/serviceinterface.h"
#include "fsfw_hal/linux/utility.h"
UartComIF::UartComIF(object_id_t objectId) : SystemObject(objectId) {} UartComIF::UartComIF(object_id_t objectId) : SystemObject(objectId) {}
UartComIF::~UartComIF() {} UartComIF::~UartComIF() {}
@ -268,6 +269,50 @@ void UartComIF::configureBaudrate(struct termios* options, UartCookie* uartCooki
cfsetispeed(options, B460800); cfsetispeed(options, B460800);
cfsetospeed(options, B460800); cfsetospeed(options, B460800);
break; break;
case 500000:
cfsetispeed(options, B500000);
cfsetospeed(options, B500000);
break;
case 576000:
cfsetispeed(options, B576000);
cfsetospeed(options, B576000);
break;
case 921600:
cfsetispeed(options, B921600);
cfsetospeed(options, B921600);
break;
case 1000000:
cfsetispeed(options, B1000000);
cfsetospeed(options, B1000000);
break;
case 1152000:
cfsetispeed(options, B1152000);
cfsetospeed(options, B1152000);
break;
case 1500000:
cfsetispeed(options, B1500000);
cfsetospeed(options, B1500000);
break;
case 2000000:
cfsetispeed(options, B2000000);
cfsetospeed(options, B2000000);
break;
case 2500000:
cfsetispeed(options, B2500000);
cfsetospeed(options, B2500000);
break;
case 3000000:
cfsetispeed(options, B3000000);
cfsetospeed(options, B3000000);
break;
case 3500000:
cfsetispeed(options, B3500000);
cfsetospeed(options, B3500000);
break;
case 4000000:
cfsetispeed(options, B4000000);
cfsetospeed(options, B4000000);
break;
default: default:
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "UartComIF::configureBaudrate: Baudrate not supported" << std::endl; sif::warning << "UartComIF::configureBaudrate: Baudrate not supported" << std::endl;

View File

@ -57,17 +57,10 @@
#define FSFW_HAL_SPI_WIRETAPPING 0 #define FSFW_HAL_SPI_WIRETAPPING 0
#endif #endif
#ifndef FSFW_HAL_L3GD20_GYRO_DEBUG // Can be used for low-level debugging of the I2C bus
#define FSFW_HAL_L3GD20_GYRO_DEBUG 0 #ifndef FSFW_HAL_I2C_WIRETAPPING
#endif /* FSFW_HAL_L3GD20_GYRO_DEBUG */ #define FSFW_HAL_I2C_WIRETAPPING 0
#endif
#ifndef FSFW_HAL_RM3100_MGM_DEBUG
#define FSFW_HAL_RM3100_MGM_DEBUG 0
#endif /* FSFW_HAL_RM3100_MGM_DEBUG */
#ifndef FSFW_HAL_LIS3MDL_MGM_DEBUG
#define FSFW_HAL_LIS3MDL_MGM_DEBUG 0
#endif /* FSFW_HAL_LIS3MDL_MGM_DEBUG */
// Can be used for low-level debugging of the I2C bus // Can be used for low-level debugging of the I2C bus
#ifndef FSFW_HAL_I2C_WIRETAPPING #ifndef FSFW_HAL_I2C_WIRETAPPING

View File

@ -12,7 +12,9 @@ object_id_t CFDPHandler::packetDestination = 0;
CFDPHandler::CFDPHandler(object_id_t setObjectId, CFDPDistributor* dist) CFDPHandler::CFDPHandler(object_id_t setObjectId, CFDPDistributor* dist)
: SystemObject(setObjectId) { : SystemObject(setObjectId) {
requestQueue = QueueFactory::instance()->createMessageQueue(CFDP_HANDLER_MAX_RECEPTION); auto mqArgs = MqArgs(setObjectId, static_cast<void*>(this));
requestQueue = QueueFactory::instance()->createMessageQueue(
CFDP_HANDLER_MAX_RECEPTION, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
distributor = dist; distributor = dist;
} }

View File

@ -13,7 +13,9 @@ ControllerBase::ControllerBase(object_id_t setObjectId, object_id_t parentId,
submode(SUBMODE_NONE), submode(SUBMODE_NONE),
modeHelper(this), modeHelper(this),
healthHelper(this, setObjectId) { healthHelper(this, setObjectId) {
commandQueue = QueueFactory::instance()->createMessageQueue(commandQueueDepth); auto mqArgs = MqArgs(setObjectId, static_cast<void*>(this));
commandQueue = QueueFactory::instance()->createMessageQueue(
commandQueueDepth, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
} }
ControllerBase::~ControllerBase() { QueueFactory::instance()->deleteMessageQueue(commandQueue); } ControllerBase::~ControllerBase() { QueueFactory::instance()->deleteMessageQueue(commandQueue); }

View File

@ -1,4 +1,4 @@
target_sources(${LIB_FSFW_NAME} PRIVATE target_sources(${LIB_FSFW_NAME} PRIVATE
PoolDataSetBase.cpp PoolDataSetBase.cpp
PoolEntry.cpp PoolEntry.cpp
) )

View File

@ -46,7 +46,7 @@ class StaticLocalDataSet : public LocalPoolDataSetBase {
} }
private: private:
std::array<PoolVariableIF*, NUM_VARIABLES> poolVarList; std::array<PoolVariableIF*, NUM_VARIABLES> poolVarList = {};
}; };
#endif /* FSFW_DATAPOOLLOCAL_STATICLOCALDATASET_H_ */ #endif /* FSFW_DATAPOOLLOCAL_STATICLOCALDATASET_H_ */

View File

@ -39,8 +39,9 @@ DeviceHandlerBase::DeviceHandlerBase(object_id_t setObjectId, object_id_t device
childTransitionDelay(5000), childTransitionDelay(5000),
transitionSourceMode(_MODE_POWER_DOWN), transitionSourceMode(_MODE_POWER_DOWN),
transitionSourceSubMode(SUBMODE_NONE) { transitionSourceSubMode(SUBMODE_NONE) {
auto mqArgs = MqArgs(setObjectId, static_cast<void*>(this));
commandQueue = QueueFactory::instance()->createMessageQueue( commandQueue = QueueFactory::instance()->createMessageQueue(
cmdQueueSize, MessageQueueMessage::MAX_MESSAGE_SIZE); cmdQueueSize, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
insertInCommandMap(RAW_COMMAND_ID); insertInCommandMap(RAW_COMMAND_ID);
cookieInfo.state = COOKIE_UNUSED; cookieInfo.state = COOKIE_UNUSED;
cookieInfo.pendingCommand = deviceCommandMap.end(); cookieInfo.pendingCommand = deviceCommandMap.end();
@ -1385,6 +1386,8 @@ void DeviceHandlerBase::setTaskIF(PeriodicTaskIF* task) { executingTask = task;
void DeviceHandlerBase::debugInterface(uint8_t positionTracker, object_id_t objectId, void DeviceHandlerBase::debugInterface(uint8_t positionTracker, object_id_t objectId,
uint32_t parameter) {} uint32_t parameter) {}
Submode_t DeviceHandlerBase::getInitialSubmode() { return SUBMODE_NONE; }
void DeviceHandlerBase::performOperationHook() {} void DeviceHandlerBase::performOperationHook() {}
ReturnValue_t DeviceHandlerBase::initializeLocalDataPool(localpool::DataPool& localDataPoolMap, ReturnValue_t DeviceHandlerBase::initializeLocalDataPool(localpool::DataPool& localDataPoolMap,
@ -1407,7 +1410,7 @@ ReturnValue_t DeviceHandlerBase::initializeAfterTaskCreation() {
this->poolManager.initializeAfterTaskCreation(); this->poolManager.initializeAfterTaskCreation();
if (setStartupImmediately) { if (setStartupImmediately) {
startTransition(MODE_ON, SUBMODE_NONE); startTransition(MODE_ON, getInitialSubmode());
} }
return HasReturnvaluesIF::RETURN_OK; return HasReturnvaluesIF::RETURN_OK;
} }

View File

@ -647,6 +647,12 @@ class DeviceHandlerBase : public DeviceHandlerIF,
virtual void debugInterface(uint8_t positionTracker = 0, object_id_t objectId = 0, virtual void debugInterface(uint8_t positionTracker = 0, object_id_t objectId = 0,
uint32_t parameter = 0); uint32_t parameter = 0);
/**
* @brief Can be overwritten by a child to specify the initial submode when device has been set
* to startup immediately.
*/
virtual Submode_t getInitialSubmode();
protected: protected:
static const uint8_t INTERFACE_ID = CLASS_ID::DEVICE_HANDLER_BASE; static const uint8_t INTERFACE_ID = CLASS_ID::DEVICE_HANDLER_BASE;

View File

@ -29,6 +29,7 @@ ReturnValue_t DeviceHandlerFailureIsolation::eventReceived(EventMessage* event)
switch (event->getEvent()) { switch (event->getEvent()) {
case HasModesIF::MODE_TRANSITION_FAILED: case HasModesIF::MODE_TRANSITION_FAILED:
case HasModesIF::OBJECT_IN_INVALID_MODE: case HasModesIF::OBJECT_IN_INVALID_MODE:
case DeviceHandlerIF::DEVICE_WANTS_HARD_REBOOT:
// We'll try a recovery as long as defined in MAX_REBOOT. // We'll try a recovery as long as defined in MAX_REBOOT.
// Might cause some AssemblyBase cycles, so keep number low. // Might cause some AssemblyBase cycles, so keep number low.
handleRecovery(event->getEvent()); handleRecovery(event->getEvent());

View File

@ -109,6 +109,7 @@ class DeviceHandlerIF {
static const Event INVALID_DEVICE_COMMAND = MAKE_EVENT(8, severity::LOW); static const Event INVALID_DEVICE_COMMAND = MAKE_EVENT(8, severity::LOW);
static const Event MONITORING_LIMIT_EXCEEDED = MAKE_EVENT(9, severity::LOW); static const Event MONITORING_LIMIT_EXCEEDED = MAKE_EVENT(9, severity::LOW);
static const Event MONITORING_AMBIGUOUS = MAKE_EVENT(10, severity::HIGH); static const Event MONITORING_AMBIGUOUS = MAKE_EVENT(10, severity::HIGH);
static const Event DEVICE_WANTS_HARD_REBOOT = MAKE_EVENT(11, severity::HIGH);
static const uint8_t INTERFACE_ID = CLASS_ID::DEVICE_HANDLER_IF; static const uint8_t INTERFACE_ID = CLASS_ID::DEVICE_HANDLER_IF;

View File

@ -8,7 +8,9 @@ HealthDevice::HealthDevice(object_id_t setObjectId, MessageQueueId_t parentQueue
parentQueue(parentQueue), parentQueue(parentQueue),
commandQueue(), commandQueue(),
healthHelper(this, setObjectId) { healthHelper(this, setObjectId) {
commandQueue = QueueFactory::instance()->createMessageQueue(3); auto mqArgs = MqArgs(setObjectId, static_cast<void*>(this));
commandQueue = QueueFactory::instance()->createMessageQueue(
3, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
} }
HealthDevice::~HealthDevice() { QueueFactory::instance()->deleteMessageQueue(commandQueue); } HealthDevice::~HealthDevice() { QueueFactory::instance()->deleteMessageQueue(commandQueue); }

View File

@ -18,8 +18,9 @@ const LocalPool::LocalPoolConfig EventManager::poolConfig = {
EventManager::EventManager(object_id_t setObjectId) EventManager::EventManager(object_id_t setObjectId)
: SystemObject(setObjectId), factoryBackend(0, poolConfig, false, true) { : SystemObject(setObjectId), factoryBackend(0, poolConfig, false, true) {
mutex = MutexFactory::instance()->createMutex(); mutex = MutexFactory::instance()->createMutex();
eventReportQueue = QueueFactory::instance()->createMessageQueue(MAX_EVENTS_PER_CYCLE, auto mqArgs = MqArgs(setObjectId, static_cast<void*>(this));
EventMessage::EVENT_MESSAGE_SIZE); eventReportQueue = QueueFactory::instance()->createMessageQueue(
MAX_EVENTS_PER_CYCLE, EventMessage::EVENT_MESSAGE_SIZE, &mqArgs);
} }
EventManager::~EventManager() { EventManager::~EventManager() {
@ -46,9 +47,20 @@ ReturnValue_t EventManager::performOperation(uint8_t opCode) {
void EventManager::notifyListeners(EventMessage* message) { void EventManager::notifyListeners(EventMessage* message) {
lockMutex(); lockMutex();
for (auto iter = listenerList.begin(); iter != listenerList.end(); ++iter) { for (auto& listener : listenerList) {
if (iter->second.match(message)) { if (listener.second.match(message)) {
MessageQueueSenderIF::sendMessage(iter->first, message, message->getSender()); ReturnValue_t result =
MessageQueueSenderIF::sendMessage(listener.first, message, message->getSender());
if (result != HasReturnvaluesIF::RETURN_OK) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::error << std::hex << "EventManager::notifyListeners: MSG to 0x" << std::setfill('0')
<< std::setw(8) << listener.first << " failed with result 0x" << std::setw(4)
<< result << std::setfill(' ') << std::endl;
#else
sif::printError("Sending message to listener 0x%08x failed with result %04x\n",
listener.first, result);
#endif
}
} }
} }
unlockMutex(); unlockMutex();
@ -189,4 +201,19 @@ void EventManager::printUtility(sif::OutputTypes printType, EventMessage* messag
} }
} }
void EventManager::printListeners() {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::info << "Event manager listener MQ IDs:" << std::setfill('0') << std::hex << std::endl;
for (auto& listener : listenerList) {
sif::info << "0x" << std::setw(8) << listener.first << std::endl;
}
sif::info << std::dec << std::setfill(' ');
#else
sif::printInfo("Event manager listener MQ IDs:\n");
for (auto& listener : listenerList) {
sif::printInfo("0x%08x\n", listener.first);
}
#endif
}
#endif /* FSFW_OBJ_EVENT_TRANSLATION == 1 */ #endif /* FSFW_OBJ_EVENT_TRANSLATION == 1 */

View File

@ -42,6 +42,7 @@ class EventManager : public EventManagerIF, public ExecutableObjectIF, public Sy
object_id_t reporterFrom = 0, object_id_t reporterTo = 0, object_id_t reporterFrom = 0, object_id_t reporterTo = 0,
bool reporterInverted = false); bool reporterInverted = false);
ReturnValue_t performOperation(uint8_t opCode); ReturnValue_t performOperation(uint8_t opCode);
void printListeners();
protected: protected:
MessageQueueIF* eventReportQueue = nullptr; MessageQueueIF* eventReportQueue = nullptr;

View File

@ -9,8 +9,9 @@
FailureIsolationBase::FailureIsolationBase(object_id_t owner, object_id_t parent, FailureIsolationBase::FailureIsolationBase(object_id_t owner, object_id_t parent,
uint8_t messageDepth, uint8_t parameterDomainBase) uint8_t messageDepth, uint8_t parameterDomainBase)
: ownerId(owner), faultTreeParent(parent), parameterDomainBase(parameterDomainBase) { : ownerId(owner), faultTreeParent(parent), parameterDomainBase(parameterDomainBase) {
eventQueue = auto mqArgs = MqArgs(owner, static_cast<void*>(this));
QueueFactory::instance()->createMessageQueue(messageDepth, EventMessage::EVENT_MESSAGE_SIZE); eventQueue = QueueFactory::instance()->createMessageQueue(
messageDepth, EventMessage::EVENT_MESSAGE_SIZE, &mqArgs);
} }
FailureIsolationBase::~FailureIsolationBase() { FailureIsolationBase::~FailureIsolationBase() {

View File

@ -14,13 +14,12 @@ class FailureIsolationBase : public HasReturnvaluesIF,
public HasParametersIF { public HasParametersIF {
public: public:
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::FDIR_1; static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::FDIR_1;
static const Event FDIR_CHANGED_STATE = //! FDIR has an internal state, which changed from par2 (oldState) to par1 (newState).
MAKE_EVENT(1, severity::INFO); //!< FDIR has an internal state, which changed from par2 static const Event FDIR_CHANGED_STATE = MAKE_EVENT(1, severity::INFO);
//!< (oldState) to par1 (newState). //! FDIR tries to restart device. Par1: event that caused recovery.
static const Event FDIR_STARTS_RECOVERY = MAKE_EVENT( static const Event FDIR_STARTS_RECOVERY = MAKE_EVENT(2, severity::MEDIUM);
2, severity::MEDIUM); //!< FDIR tries to restart device. Par1: event that caused recovery. //! FDIR turns off device. Par1: event that caused recovery.
static const Event FDIR_TURNS_OFF_DEVICE = MAKE_EVENT( static const Event FDIR_TURNS_OFF_DEVICE = MAKE_EVENT(3, severity::MEDIUM);
3, severity::MEDIUM); //!< FDIR turns off device. Par1: event that caused recovery.
FailureIsolationBase(object_id_t owner, object_id_t parent = objects::NO_OBJECT, FailureIsolationBase(object_id_t owner, object_id_t parent = objects::NO_OBJECT,
uint8_t messageDepth = 10, uint8_t parameterDomainBase = 0xF0); uint8_t messageDepth = 10, uint8_t parameterDomainBase = 0xF0);

View File

@ -23,19 +23,15 @@ class HasHealthIF {
static const Event HEALTH_INFO = MAKE_EVENT(6, severity::INFO); static const Event HEALTH_INFO = MAKE_EVENT(6, severity::INFO);
static const Event CHILD_CHANGED_HEALTH = MAKE_EVENT(7, severity::INFO); static const Event CHILD_CHANGED_HEALTH = MAKE_EVENT(7, severity::INFO);
static const Event CHILD_PROBLEMS = MAKE_EVENT(8, severity::LOW); static const Event CHILD_PROBLEMS = MAKE_EVENT(8, severity::LOW);
static const Event OVERWRITING_HEALTH = //! Assembly overwrites health information of children to keep satellite alive.
MAKE_EVENT(9, severity::LOW); //!< Assembly overwrites health information of children to keep static const Event OVERWRITING_HEALTH = MAKE_EVENT(9, severity::LOW);
//!< satellite alive. //! Someone starts a recovery of a component (typically power-cycle). No parameters.
static const Event TRYING_RECOVERY = static const Event TRYING_RECOVERY = MAKE_EVENT(10, severity::MEDIUM);
MAKE_EVENT(10, severity::MEDIUM); //!< Someone starts a recovery of a component (typically //! Recovery is ongoing. Comes twice during recovery.
//!< power-cycle). No parameters. //! P1: 0 for the first, 1 for the second event. P2: 0
static const Event RECOVERY_STEP = static const Event RECOVERY_STEP = MAKE_EVENT(11, severity::MEDIUM);
MAKE_EVENT(11, severity::MEDIUM); //!< Recovery is ongoing. Comes twice during recovery. P1: //! Recovery was completed. Not necessarily successful. No parameters.
//!< 0 for the first, 1 for the second event. P2: 0 static const Event RECOVERY_DONE = MAKE_EVENT(12, severity::MEDIUM);
static const Event RECOVERY_DONE = MAKE_EVENT(
12,
severity::MEDIUM); //!< Recovery was completed. Not necessarily successful. No parameters.
virtual ~HasHealthIF() {} virtual ~HasHealthIF() {}
virtual MessageQueueId_t getCommandQueue() const = 0; virtual MessageQueueId_t getCommandQueue() const = 0;

View File

@ -7,11 +7,13 @@
InternalErrorReporter::InternalErrorReporter(object_id_t setObjectId, uint32_t messageQueueDepth) InternalErrorReporter::InternalErrorReporter(object_id_t setObjectId, uint32_t messageQueueDepth)
: SystemObject(setObjectId), : SystemObject(setObjectId),
commandQueue(QueueFactory::instance()->createMessageQueue(messageQueueDepth)),
poolManager(this, commandQueue), poolManager(this, commandQueue),
internalErrorSid(setObjectId, InternalErrorDataset::ERROR_SET_ID), internalErrorSid(setObjectId, InternalErrorDataset::ERROR_SET_ID),
internalErrorDataset(this) { internalErrorDataset(this) {
mutex = MutexFactory::instance()->createMutex(); mutex = MutexFactory::instance()->createMutex();
auto mqArgs = MqArgs(setObjectId, static_cast<void *>(this));
commandQueue = QueueFactory::instance()->createMessageQueue(
messageQueueDepth, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
} }
InternalErrorReporter::~InternalErrorReporter() { MutexFactory::instance()->deleteMutex(mutex); } InternalErrorReporter::~InternalErrorReporter() { MutexFactory::instance()->deleteMutex(mutex); }
@ -36,15 +38,14 @@ ReturnValue_t InternalErrorReporter::performOperation(uint8_t opCode) {
if ((newQueueHits > 0) or (newTmHits > 0) or (newStoreHits > 0)) { if ((newQueueHits > 0) or (newTmHits > 0) or (newStoreHits > 0)) {
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::debug << "InternalErrorReporter::performOperation: Errors " sif::debug << "InternalErrorReporter::performOperation: Errors "
<< "occured!" << std::endl; << "occured: Queue | TM | Store : " << newQueueHits << " | " << newTmHits << " | "
sif::debug << "Queue errors: " << newQueueHits << std::endl; << newStoreHits << std::endl;
sif::debug << "TM errors: " << newTmHits << std::endl;
sif::debug << "Store errors: " << newStoreHits << std::endl;
#else #else
sif::printDebug("InternalErrorReporter::performOperation: Errors occured!\n"); sif::printDebug(
sif::printDebug("Queue errors: %lu\n", static_cast<unsigned int>(newQueueHits)); "InternalErrorReporter::performOperation: Errors occured: Queue | TM | Store: %lu | %lu "
sif::printDebug("TM errors: %lu\n", static_cast<unsigned int>(newTmHits)); "| %lu\n",
sif::printDebug("Store errors: %lu\n", static_cast<unsigned int>(newStoreHits)); static_cast<unsigned int>(newQueueHits), static_cast<unsigned int>(newTmHits),
static_cast<unsigned int>(newStoreHits));
#endif #endif
} }
} }

View File

@ -5,6 +5,7 @@
#include "MessageQueueIF.h" #include "MessageQueueIF.h"
#include "MessageQueueMessage.h" #include "MessageQueueMessage.h"
#include "definitions.h"
/** /**
* Creates message queues. * Creates message queues.
@ -22,7 +23,8 @@ class QueueFactory {
static QueueFactory* instance(); static QueueFactory* instance();
MessageQueueIF* createMessageQueue(uint32_t messageDepth = 3, MessageQueueIF* createMessageQueue(uint32_t messageDepth = 3,
size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE); size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE,
MqArgs* args = nullptr);
void deleteMessageQueue(MessageQueueIF* queue); void deleteMessageQueue(MessageQueueIF* queue);

View File

@ -0,0 +1,12 @@
#ifndef FSFW_SRC_FSFW_IPC_DEFINITIONS_H_
#define FSFW_SRC_FSFW_IPC_DEFINITIONS_H_
#include <fsfw/objectmanager/SystemObjectIF.h>
struct MqArgs {
MqArgs(){};
MqArgs(object_id_t objectId, void* args = nullptr) : objectId(objectId), args(args) {}
object_id_t objectId = 0;
void* args = nullptr;
};
#endif /* FSFW_SRC_FSFW_IPC_DEFINITIONS_H_ */

View File

@ -19,32 +19,29 @@ class HasModesIF {
static const ReturnValue_t INVALID_SUBMODE = MAKE_RETURN_CODE(0x04); static const ReturnValue_t INVALID_SUBMODE = MAKE_RETURN_CODE(0x04);
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::SYSTEM_MANAGER; static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::SYSTEM_MANAGER;
static const Event CHANGING_MODE = //! An object announces changing the mode. p1: target mode. p2: target submode
MAKE_EVENT(0, severity::INFO); //!< An object announces changing the mode. p1: target mode. static const Event CHANGING_MODE = MAKE_EVENT(0, severity::INFO);
//!< p2: target submode //! An Object announces its mode; parameter1 is mode, parameter2 is submode
static const Event MODE_INFO = MAKE_EVENT( static const Event MODE_INFO = MAKE_EVENT(1, severity::INFO);
1,
severity::INFO); //!< An Object announces its mode; parameter1 is mode, parameter2 is submode
static const Event FALLBACK_FAILED = MAKE_EVENT(2, severity::HIGH); static const Event FALLBACK_FAILED = MAKE_EVENT(2, severity::HIGH);
static const Event MODE_TRANSITION_FAILED = MAKE_EVENT(3, severity::LOW); static const Event MODE_TRANSITION_FAILED = MAKE_EVENT(3, severity::LOW);
static const Event CANT_KEEP_MODE = MAKE_EVENT(4, severity::HIGH); static const Event CANT_KEEP_MODE = MAKE_EVENT(4, severity::HIGH);
static const Event OBJECT_IN_INVALID_MODE = //! Indicates a bug or configuration failure: Object is in a mode it should never be in.
MAKE_EVENT(5, severity::LOW); //!< Indicates a bug or configuration failure: Object is in a static const Event OBJECT_IN_INVALID_MODE = MAKE_EVENT(5, severity::LOW);
//!< mode it should never be in. //! The mode is changed, but for some reason, the change is forced, i.e. EXTERNAL_CONTROL ignored.
static const Event FORCING_MODE = MAKE_EVENT( //! p1: target mode. p2: target submode
6, severity::MEDIUM); //!< The mode is changed, but for some reason, the change is forced, static const Event FORCING_MODE = MAKE_EVENT(6, severity::MEDIUM);
//!< i.e. EXTERNAL_CONTROL ignored. p1: target mode. p2: target submode //! A mode command was rejected by the called object. Par1: called object id, Par2: return code.
static const Event MODE_CMD_REJECTED = static const Event MODE_CMD_REJECTED = MAKE_EVENT(7, severity::LOW);
MAKE_EVENT(7, severity::LOW); //!< A mode command was rejected by the called object. Par1:
//!< called object id, Par2: return code.
static const Mode_t MODE_ON = //! The device is powered and ready to perform operations. In this mode, no commands are
1; //!< The device is powered and ready to perform operations. In this mode, no commands are //! sent by the device handler itself, but direct commands van be commanded and will be
//!< sent by the device handler itself, but direct commands van be commanded and will be //! interpreted
//!< interpreted static const Mode_t MODE_ON = 1;
static const Mode_t MODE_OFF = 0; //!< The device is powered off. The only command accepted in //! The device is powered off. The only command accepted in this mode is a mode change to on.
//!< this mode is a mode change to on. static const Mode_t MODE_OFF = 0;
static const Submode_t SUBMODE_NONE = 0; //!< To avoid checks against magic number "0". //! To avoid checks against magic number "0".
static const Submode_t SUBMODE_NONE = 0;
virtual ~HasModesIF() {} virtual ~HasModesIF() {}
virtual MessageQueueId_t getCommandQueue() const = 0; virtual MessageQueueId_t getCommandQueue() const = 0;

View File

@ -95,13 +95,16 @@ void ObjectManager::initialize() {
for (auto const& it : objectList) { for (auto const& it : objectList) {
result = it.second->initialize(); result = it.second->initialize();
if (result != RETURN_OK) { if (result != RETURN_OK) {
#if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
object_id_t var = it.first;
sif::error << "ObjectManager::initialize: Object 0x" << std::hex << std::setw(8) sif::error << "ObjectManager::initialize: Object 0x" << std::hex << std::setw(8)
<< std::setfill('0') << var << std::setfill('0') << it.first << " failed to initialize with code 0x" << result
<< " failed to " << std::dec << std::setfill(' ') << std::endl;
"initialize with code 0x" #else
<< result << std::dec << std::setfill(' ') << std::endl; sif::printError(
"ObjectManager::initialize: Object 0x%08x failed to initialize with code 0x%04x\n", var,
it.first);
#endif
#endif #endif
errorCount++; errorCount++;
} }

View File

@ -4,7 +4,7 @@
#include "fsfw/osal/freertos/QueueMapManager.h" #include "fsfw/osal/freertos/QueueMapManager.h"
#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/serviceinterface/ServiceInterface.h"
MessageQueue::MessageQueue(size_t messageDepth, size_t maxMessageSize) MessageQueue::MessageQueue(size_t messageDepth, size_t maxMessageSize, MqArgs* args)
: maxMessageSize(maxMessageSize) { : maxMessageSize(maxMessageSize) {
handle = xQueueCreate(messageDepth, maxMessageSize); handle = xQueueCreate(messageDepth, maxMessageSize);
if (handle == nullptr) { if (handle == nullptr) {

View File

@ -7,6 +7,7 @@
#include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/ipc/MessageQueueIF.h"
#include "fsfw/ipc/MessageQueueMessage.h" #include "fsfw/ipc/MessageQueueMessage.h"
#include "fsfw/ipc/MessageQueueMessageIF.h" #include "fsfw/ipc/MessageQueueMessageIF.h"
#include "fsfw/ipc/definitions.h"
#include "queue.h" #include "queue.h"
/** /**
@ -53,7 +54,8 @@ class MessageQueue : public MessageQueueIF {
* This should be left default. * This should be left default.
*/ */
MessageQueue(size_t messageDepth = 3, MessageQueue(size_t messageDepth = 3,
size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE); size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE,
MqArgs* args = nullptr);
/** Copying message queues forbidden */ /** Copying message queues forbidden */
MessageQueue(const MessageQueue&) = delete; MessageQueue(const MessageQueue&) = delete;

View File

@ -22,8 +22,9 @@ QueueFactory::QueueFactory() {}
QueueFactory::~QueueFactory() {} QueueFactory::~QueueFactory() {}
MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, size_t maxMessageSize) { MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, size_t maxMessageSize,
return new MessageQueue(messageDepth, maxMessageSize); MqArgs* args) {
return new MessageQueue(messageDepth, maxMessageSize, args);
} }
void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { delete queue; } void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { delete queue; }

View File

@ -8,7 +8,7 @@
#include "fsfw/osal/host/QueueMapManager.h" #include "fsfw/osal/host/QueueMapManager.h"
#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/serviceinterface/ServiceInterface.h"
MessageQueue::MessageQueue(size_t messageDepth, size_t maxMessageSize) MessageQueue::MessageQueue(size_t messageDepth, size_t maxMessageSize, MqArgs* args)
: messageSize(maxMessageSize), messageDepth(messageDepth) { : messageSize(maxMessageSize), messageDepth(messageDepth) {
queueLock = MutexFactory::instance()->createMutex(); queueLock = MutexFactory::instance()->createMutex();
auto result = QueueMapManager::instance()->addMessageQueue(this, &mqId); auto result = QueueMapManager::instance()->addMessageQueue(this, &mqId);

View File

@ -8,6 +8,7 @@
#include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/ipc/MessageQueueIF.h"
#include "fsfw/ipc/MessageQueueMessage.h" #include "fsfw/ipc/MessageQueueMessage.h"
#include "fsfw/ipc/MutexIF.h" #include "fsfw/ipc/MutexIF.h"
#include "fsfw/ipc/definitions.h"
#include "fsfw/timemanager/Clock.h" #include "fsfw/timemanager/Clock.h"
/** /**
@ -54,7 +55,8 @@ class MessageQueue : public MessageQueueIF {
* This should be left default. * This should be left default.
*/ */
MessageQueue(size_t messageDepth = 3, MessageQueue(size_t messageDepth = 3,
size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE); size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE,
MqArgs* args = nullptr);
/** Copying message queues forbidden */ /** Copying message queues forbidden */
MessageQueue(const MessageQueue&) = delete; MessageQueue(const MessageQueue&) = delete;

View File

@ -27,12 +27,13 @@ QueueFactory::QueueFactory() {}
QueueFactory::~QueueFactory() {} QueueFactory::~QueueFactory() {}
MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, size_t maxMessageSize) { MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, size_t maxMessageSize,
MqArgs* args) {
// A thread-safe queue can be implemented by using a combination // A thread-safe queue can be implemented by using a combination
// of std::queue and std::mutex. This uses dynamic memory allocation // of std::queue and std::mutex. This uses dynamic memory allocation
// which could be alleviated by using a custom allocator, external library // which could be alleviated by using a custom allocator, external library
// (etl::queue) or simply using std::queue, we're on a host machine anyway. // (etl::queue) or simply using std::queue, we're on a host machine anyway.
return new MessageQueue(messageDepth, maxMessageSize); return new MessageQueue(messageDepth, maxMessageSize, args);
} }
void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { delete queue; } void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { delete queue; }

View File

@ -11,7 +11,7 @@
#include "fsfw/osal/linux/unixUtility.h" #include "fsfw/osal/linux/unixUtility.h"
#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/serviceinterface/ServiceInterface.h"
MessageQueue::MessageQueue(uint32_t messageDepth, size_t maxMessageSize) MessageQueue::MessageQueue(uint32_t messageDepth, size_t maxMessageSize, MqArgs* args)
: id(MessageQueueIF::NO_QUEUE), : id(MessageQueueIF::NO_QUEUE),
lastPartner(MessageQueueIF::NO_QUEUE), lastPartner(MessageQueueIF::NO_QUEUE),
defaultDestination(MessageQueueIF::NO_QUEUE), defaultDestination(MessageQueueIF::NO_QUEUE),
@ -37,6 +37,9 @@ MessageQueue::MessageQueue(uint32_t messageDepth, size_t maxMessageSize)
// Successful mq_open call // Successful mq_open call
this->id = tempId; this->id = tempId;
} }
if (args != nullptr) {
this->mqArgs = *args;
}
} }
MessageQueue::~MessageQueue() { MessageQueue::~MessageQueue() {
@ -240,9 +243,9 @@ ReturnValue_t MessageQueue::sendMessageFromMessageQueue(MessageQueueId_t sendTo,
bool ignoreFault) { bool ignoreFault) {
if (message == nullptr) { if (message == nullptr) {
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::error << "MessageQueue::sendMessageFromMessageQueue: Message is nullptr!" << std::endl; sif::error << "MessageQueue::sendMessageFromMessageQueue: Message is nullptr" << std::endl;
#else #else
sif::printError("MessageQueue::sendMessageFromMessageQueue: Message is nullptr!\n"); sif::printError("MessageQueue::sendMessageFromMessageQueue: Message is nullptr\n");
#endif #endif
return HasReturnvaluesIF::RETURN_FAILED; return HasReturnvaluesIF::RETURN_FAILED;
} }
@ -256,7 +259,7 @@ ReturnValue_t MessageQueue::sendMessageFromMessageQueue(MessageQueueId_t sendTo,
if (!ignoreFault) { if (!ignoreFault) {
InternalErrorReporterIF* internalErrorReporter = InternalErrorReporterIF* internalErrorReporter =
ObjectManager::instance()->get<InternalErrorReporterIF>(objects::INTERNAL_ERROR_REPORTER); ObjectManager::instance()->get<InternalErrorReporterIF>(objects::INTERNAL_ERROR_REPORTER);
if (internalErrorReporter != NULL) { if (internalErrorReporter != nullptr) {
internalErrorReporter->queueMessageNotSent(); internalErrorReporter->queueMessageNotSent();
} }
} }

View File

@ -6,6 +6,7 @@
#include "fsfw/internalerror/InternalErrorReporterIF.h" #include "fsfw/internalerror/InternalErrorReporterIF.h"
#include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/ipc/MessageQueueIF.h"
#include "fsfw/ipc/MessageQueueMessage.h" #include "fsfw/ipc/MessageQueueMessage.h"
#include "fsfw/ipc/definitions.h"
/** /**
* @brief This class manages sending and receiving of message queue messages. * @brief This class manages sending and receiving of message queue messages.
* *
@ -42,7 +43,8 @@ class MessageQueue : public MessageQueueIF {
* This should be left default. * This should be left default.
*/ */
MessageQueue(uint32_t messageDepth = 3, MessageQueue(uint32_t messageDepth = 3,
size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE); size_t maxMessageSize = MessageQueueMessage::MAX_MESSAGE_SIZE,
MqArgs* args = nullptr);
/** /**
* @brief The destructor deletes the formerly created message queue. * @brief The destructor deletes the formerly created message queue.
* @details This is accomplished by using the delete call provided by the operating system. * @details This is accomplished by using the delete call provided by the operating system.
@ -184,6 +186,8 @@ class MessageQueue : public MessageQueueIF {
*/ */
char name[16]; char name[16];
MqArgs mqArgs = {};
static uint16_t queueCounter; static uint16_t queueCounter;
const size_t maxMessageSize; const size_t maxMessageSize;

View File

@ -28,8 +28,9 @@ QueueFactory::QueueFactory() {}
QueueFactory::~QueueFactory() {} QueueFactory::~QueueFactory() {}
MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, size_t maxMessageSize) { MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, size_t maxMessageSize,
return new MessageQueue(messageDepth, maxMessageSize); MqArgs* args) {
return new MessageQueue(messageDepth, maxMessageSize, args);
} }
void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { delete queue; } void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { delete queue; }

View File

@ -6,7 +6,7 @@
#include "fsfw/osal/rtems/RtemsBasic.h" #include "fsfw/osal/rtems/RtemsBasic.h"
#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/serviceinterface/ServiceInterface.h"
MessageQueue::MessageQueue(size_t message_depth, size_t max_message_size) MessageQueue::MessageQueue(size_t message_depth, size_t max_message_size, MqArgs* args)
: id(0), lastPartner(0), defaultDestination(NO_QUEUE), internalErrorReporter(nullptr) { : id(0), lastPartner(0), defaultDestination(NO_QUEUE), internalErrorReporter(nullptr) {
rtems_name name = ('Q' << 24) + (queueCounter++ << 8); rtems_name name = ('Q' << 24) + (queueCounter++ << 8);
rtems_status_code status = rtems_status_code status =

View File

@ -5,6 +5,7 @@
#include "fsfw/internalerror/InternalErrorReporterIF.h" #include "fsfw/internalerror/InternalErrorReporterIF.h"
#include "fsfw/ipc/MessageQueueIF.h" #include "fsfw/ipc/MessageQueueIF.h"
#include "fsfw/ipc/MessageQueueMessage.h" #include "fsfw/ipc/MessageQueueMessage.h"
#include "fsfw/ipc/definitions.h"
/** /**
* @brief This class manages sending and receiving of message queue messages. * @brief This class manages sending and receiving of message queue messages.
@ -34,7 +35,8 @@ class MessageQueue : public MessageQueueIF {
* This should be left default. * This should be left default.
*/ */
MessageQueue(size_t message_depth = 3, MessageQueue(size_t message_depth = 3,
size_t max_message_size = MessageQueueMessage::MAX_MESSAGE_SIZE); size_t max_message_size = MessageQueueMessage::MAX_MESSAGE_SIZE,
MqArgs* args = nullptr);
/** /**
* @brief The destructor deletes the formerly created message queue. * @brief The destructor deletes the formerly created message queue.
* @details This is accomplished by using the delete call provided by the operating system. * @details This is accomplished by using the delete call provided by the operating system.

View File

@ -49,8 +49,9 @@ QueueFactory::QueueFactory() {}
QueueFactory::~QueueFactory() {} QueueFactory::~QueueFactory() {}
MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, size_t maxMessageSize) { MessageQueueIF* QueueFactory::createMessageQueue(uint32_t messageDepth, size_t maxMessageSize,
return new MessageQueue(messageDepth, maxMessageSize); MqArgs* args) {
return new MessageQueue(messageDepth, maxMessageSize, args);
} }
void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { delete queue; } void QueueFactory::deleteMessageQueue(MessageQueueIF* queue) { delete queue; }

View File

@ -34,14 +34,14 @@ class Fuse : public SystemObject,
}; };
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PCDU_1; static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PCDU_1;
static const Event FUSE_CURRENT_HIGH = MAKE_EVENT( //! PSS detected that current on a fuse is totally out of bounds.
1, severity::LOW); //!< PSS detected that current on a fuse is totally out of bounds. static const Event FUSE_CURRENT_HIGH = MAKE_EVENT(1, severity::LOW);
static const Event FUSE_WENT_OFF = //! PSS detected a fuse that went off.
MAKE_EVENT(2, severity::LOW); //!< PSS detected a fuse that went off. static const Event FUSE_WENT_OFF = MAKE_EVENT(2, severity::LOW);
static const Event POWER_ABOVE_HIGH_LIMIT = //! PSS detected a fuse that violates its limits.
MAKE_EVENT(4, severity::LOW); //!< PSS detected a fuse that violates its limits. static const Event POWER_ABOVE_HIGH_LIMIT = MAKE_EVENT(4, severity::LOW);
static const Event POWER_BELOW_LOW_LIMIT = //! PSS detected a fuse that violates its limits.
MAKE_EVENT(5, severity::LOW); //!< PSS detected a fuse that violates its limits. static const Event POWER_BELOW_LOW_LIMIT = MAKE_EVENT(5, severity::LOW);
typedef std::list<PowerComponentIF *> DeviceList; typedef std::list<PowerComponentIF *> DeviceList;
Fuse(object_id_t fuseObjectId, uint8_t fuseId, sid_t variableSet, VariableIds ids, Fuse(object_id_t fuseObjectId, uint8_t fuseId, sid_t variableSet, VariableIds ids,

View File

@ -15,7 +15,9 @@ PowerSensor::PowerSensor(object_id_t objectId, sid_t setId, VariableIds ids, Def
limits.currentMin, limits.currentMax, events.currentLow, events.currentHigh), limits.currentMin, limits.currentMax, events.currentLow, events.currentHigh),
voltageLimit(objectId, MODULE_ID_VOLTAGE, ids.pidVoltage, confirmationCount, voltageLimit(objectId, MODULE_ID_VOLTAGE, ids.pidVoltage, confirmationCount,
limits.voltageMin, limits.voltageMax, events.voltageLow, events.voltageHigh) { limits.voltageMin, limits.voltageMax, events.voltageLow, events.voltageHigh) {
commandQueue = QueueFactory::instance()->createMessageQueue(); auto mqArgs = MqArgs(objectId, static_cast<void*>(this));
commandQueue = QueueFactory::instance()->createMessageQueue(
3, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
} }
PowerSensor::~PowerSensor() { QueueFactory::instance()->deleteMessageQueue(commandQueue); } PowerSensor::~PowerSensor() { QueueFactory::instance()->deleteMessageQueue(commandQueue); }

View File

@ -16,7 +16,9 @@ Service1TelecommandVerification::Service1TelecommandVerification(object_id_t obj
apid(apid), apid(apid),
serviceId(serviceId), serviceId(serviceId),
targetDestination(targetDestination) { targetDestination(targetDestination) {
tmQueue = QueueFactory::instance()->createMessageQueue(messageQueueDepth); auto mqArgs = MqArgs(objectId, static_cast<void*>(this));
tmQueue = QueueFactory::instance()->createMessageQueue(
messageQueueDepth, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
} }
Service1TelecommandVerification::~Service1TelecommandVerification() { Service1TelecommandVerification::~Service1TelecommandVerification() {

View File

@ -12,7 +12,9 @@ Service5EventReporting::Service5EventReporting(object_id_t objectId, uint16_t ap
uint32_t messageQueueDepth) uint32_t messageQueueDepth)
: PusServiceBase(objectId, apid, serviceId), : PusServiceBase(objectId, apid, serviceId),
maxNumberReportsPerCycle(maxNumberReportsPerCycle) { maxNumberReportsPerCycle(maxNumberReportsPerCycle) {
eventQueue = QueueFactory::instance()->createMessageQueue(messageQueueDepth); auto mqArgs = MqArgs(objectId, static_cast<void*>(this));
eventQueue = QueueFactory::instance()->createMessageQueue(
messageQueueDepth, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
} }
Service5EventReporting::~Service5EventReporting() { Service5EventReporting::~Service5EventReporting() {
@ -36,9 +38,6 @@ ReturnValue_t Service5EventReporting::performService() {
} }
} }
} }
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "Service5EventReporting::generateEventReport: Too many events" << std::endl;
#endif
return HasReturnvaluesIF::RETURN_OK; return HasReturnvaluesIF::RETURN_OK;
} }
@ -87,7 +86,7 @@ ReturnValue_t Service5EventReporting::handleRequest(uint8_t subservice) {
// to be registered to the event manager to listen for events. // to be registered to the event manager to listen for events.
ReturnValue_t Service5EventReporting::initialize() { ReturnValue_t Service5EventReporting::initialize() {
EventManagerIF* manager = ObjectManager::instance()->get<EventManagerIF>(objects::EVENT_MANAGER); EventManagerIF* manager = ObjectManager::instance()->get<EventManagerIF>(objects::EVENT_MANAGER);
if (manager == NULL) { if (manager == nullptr) {
return RETURN_FAILED; return RETURN_FAILED;
} }
// register Service 5 as listener for events // register Service 5 as listener for events

View File

@ -41,7 +41,7 @@
class Service5EventReporting : public PusServiceBase { class Service5EventReporting : public PusServiceBase {
public: public:
Service5EventReporting(object_id_t objectId, uint16_t apid, uint8_t serviceId, Service5EventReporting(object_id_t objectId, uint16_t apid, uint8_t serviceId,
size_t maxNumberReportsPerCycle = 10, uint32_t messageQueueDepth = 10); size_t maxNumberReportsPerCycle, uint32_t messageQueueDepth);
virtual ~Service5EventReporting(); virtual ~Service5EventReporting();
/*** /***

View File

@ -6,10 +6,10 @@
class Service9TimeManagement : public PusServiceBase { class Service9TimeManagement : public PusServiceBase {
public: public:
static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PUS_SERVICE_9; static constexpr uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::PUS_SERVICE_9;
static constexpr Event CLOCK_SET = //!< Clock has been set. P1: New Uptime. P2: Old Uptime
MAKE_EVENT(0, severity::INFO); //!< Clock has been set. P1: New Uptime. P2: Old Uptime static constexpr Event CLOCK_SET = MAKE_EVENT(0, severity::INFO);
static constexpr Event CLOCK_SET_FAILURE = //!< Clock could not be set. P1: Returncode.
MAKE_EVENT(1, severity::LOW); //!< Clock could not be set. P1: Returncode. static constexpr Event CLOCK_SET_FAILURE = MAKE_EVENT(1, severity::LOW);
static constexpr uint8_t CLASS_ID = CLASS_ID::PUS_SERVICE_9; static constexpr uint8_t CLASS_ID = CLASS_ID::PUS_SERVICE_9;

View File

@ -169,8 +169,8 @@ class RMAP : public HasReturnvaluesIF {
* @param buffer the data to write * @param buffer the data to write
* @param length length of data * @param length length of data
* @return * @return
* - @c COMMAND_NULLPOINTER datalen was != 0 but data was == NULL * - @c COMMAND_NULLPOINTER datalen was != 0 but data was ==
* in write command * NULL in write command
* - return codes of RMAPChannelIF::sendCommand() * - return codes of RMAPChannelIF::sendCommand()
*/ */
static ReturnValue_t sendWriteCommand(RMAPCookie *cookie, const uint8_t *buffer, size_t length); static ReturnValue_t sendWriteCommand(RMAPCookie *cookie, const uint8_t *buffer, size_t length);
@ -205,8 +205,8 @@ class RMAP : public HasReturnvaluesIF {
* @param cookie to cookie to read from * @param cookie to cookie to read from
* @param expLength the expected maximum length of the reply * @param expLength the expected maximum length of the reply
* @return * @return
* - @c COMMAND_NULLPOINTER datalen was != 0 but data was == NULL * - @c COMMAND_NULLPOINTER datalen was != 0 but data was ==
* in write command, or nullpointer in read command * NULL in write command, or nullpointer in read command
* - return codes of RMAPChannelIF::sendCommand() * - return codes of RMAPChannelIF::sendCommand()
*/ */
static ReturnValue_t sendReadCommand(RMAPCookie *cookie, uint32_t expLength); static ReturnValue_t sendReadCommand(RMAPCookie *cookie, uint32_t expLength);

View File

@ -75,11 +75,21 @@ class RMAPChannelIF {
* - @c RETURN_OK * - @c RETURN_OK
* - @c COMMAND_NO_DESCRIPTORS_AVAILABLE no descriptors available for sending * - @c COMMAND_NO_DESCRIPTORS_AVAILABLE no descriptors available for sending
* command; command was not sent * command; command was not sent
* - @c COMMAND_BUFFER_FULL no receiver buffer available for expected <<<<<<< HEAD
* - @c COMMAND_BUFFER_FULL no receiver buffer available for
expected
* len; command was not sent * len; command was not sent
* - @c COMMAND_TOO_BIG the data that was to be sent was too long for the * - @c COMMAND_TOO_BIG the data that was to be sent was too long for
the
* hw to handle (write command) or the expected len was bigger than maximal expected len (read * hw to handle (write command) or the expected len was bigger than maximal expected len (read
* command) command was not sent * command) command was not sent
=======
* - @c COMMAND_BUFFER_FULL no receiver buffer available for
* expected len; command was not sent
* - @c COMMAND_TOO_BIG the data that was to be sent was too
* long for the hw to handle (write command) or the expected len was bigger than maximal expected
* len (read command) command was not sent
>>>>>>> origin/eive/develop
* - @c COMMAND_CHANNEL_DEACTIVATED the channel has no port set * - @c COMMAND_CHANNEL_DEACTIVATED the channel has no port set
* - @c NOT_SUPPORTED if you dont feel like * - @c NOT_SUPPORTED if you dont feel like
* implementing something... * implementing something...
@ -97,8 +107,14 @@ class RMAPChannelIF {
* - @c REPLY_NO_REPLY no reply was received * - @c REPLY_NO_REPLY no reply was received
* - @c REPLY_NOT_SENT command was not sent, implies no reply * - @c REPLY_NOT_SENT command was not sent, implies no reply
* - @c REPLY_NOT_YET_SENT command is still waiting to be sent * - @c REPLY_NOT_YET_SENT command is still waiting to be sent
* - @c WRITE_REPLY_INTERFACE_BUSY Interface is busy (transmission buffer <<<<<<< HEAD
* - @c WRITE_REPLY_INTERFACE_BUSY Interface is busy (transmission
buffer
* still being processed) * still being processed)
=======
* - @c WRITE_REPLY_INTERFACE_BUSY Interface is busy (transmission
* buffer still being processed)
>>>>>>> origin/eive/develop
* - @c WRITE_REPLY_TRANSMISSION_ERROR Interface encountered errors during last * - @c WRITE_REPLY_TRANSMISSION_ERROR Interface encountered errors during last
* operation, data could not be processed. (transmission error) * operation, data could not be processed. (transmission error)
* - @c WRITE_REPLY_INVALID_DATA Invalid data (amount / value) * - @c WRITE_REPLY_INVALID_DATA Invalid data (amount / value)

View File

@ -8,11 +8,13 @@ SubsystemBase::SubsystemBase(object_id_t setObjectId, object_id_t parent, Mode_t
uint16_t commandQueueDepth) uint16_t commandQueueDepth)
: SystemObject(setObjectId), : SystemObject(setObjectId),
mode(initialMode), mode(initialMode),
commandQueue(QueueFactory::instance()->createMessageQueue(commandQueueDepth,
CommandMessage::MAX_MESSAGE_SIZE)),
healthHelper(this, setObjectId), healthHelper(this, setObjectId),
modeHelper(this), modeHelper(this),
parentId(parent) {} parentId(parent) {
auto mqArgs = MqArgs(setObjectId, static_cast<void*>(this));
commandQueue = QueueFactory::instance()->createMessageQueue(
commandQueueDepth, CommandMessage::MAX_MESSAGE_SIZE, &mqArgs);
}
SubsystemBase::~SubsystemBase() { QueueFactory::instance()->deleteMessageQueue(commandQueue); } SubsystemBase::~SubsystemBase() { QueueFactory::instance()->deleteMessageQueue(commandQueue); }

View File

@ -5,7 +5,9 @@
#include "fsfw/tmtcservices/TmTcMessage.h" #include "fsfw/tmtcservices/TmTcMessage.h"
TcDistributor::TcDistributor(object_id_t objectId) : SystemObject(objectId) { TcDistributor::TcDistributor(object_id_t objectId) : SystemObject(objectId) {
tcQueue = QueueFactory::instance()->createMessageQueue(DISTRIBUTER_MAX_PACKETS); auto mqArgs = MqArgs(objectId);
tcQueue = QueueFactory::instance()->createMessageQueue(
DISTRIBUTER_MAX_PACKETS, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
} }
TcDistributor::~TcDistributor() { QueueFactory::instance()->deleteMessageQueue(tcQueue); } TcDistributor::~TcDistributor() { QueueFactory::instance()->deleteMessageQueue(tcQueue); }

View File

@ -4,14 +4,13 @@
AbstractTemperatureSensor::AbstractTemperatureSensor(object_id_t setObjectid, AbstractTemperatureSensor::AbstractTemperatureSensor(object_id_t setObjectid,
ThermalModuleIF *thermalModule) ThermalModuleIF *thermalModule)
: SystemObject(setObjectid), : SystemObject(setObjectid), healthHelper(this, setObjectid), parameterHelper(this) {
commandQueue(NULL), if (thermalModule != nullptr) {
healthHelper(this, setObjectid),
parameterHelper(this) {
if (thermalModule != NULL) {
thermalModule->registerSensor(this); thermalModule->registerSensor(this);
} }
commandQueue = QueueFactory::instance()->createMessageQueue(); auto mqArgs = MqArgs(setObjectid, static_cast<void *>(this));
commandQueue = QueueFactory::instance()->createMessageQueue(
3, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
} }
AbstractTemperatureSensor::~AbstractTemperatureSensor() { AbstractTemperatureSensor::~AbstractTemperatureSensor() {

View File

@ -51,7 +51,7 @@ class AbstractTemperatureSensor : public HasHealthIF,
HasHealthIF::HealthState getHealth(); HasHealthIF::HealthState getHealth();
protected: protected:
MessageQueueIF* commandQueue; MessageQueueIF* commandQueue = nullptr;
HealthHelper healthHelper; HealthHelper healthHelper;
ParameterHelper parameterHelper; ParameterHelper parameterHelper;

View File

@ -12,7 +12,9 @@ Heater::Heater(uint32_t objectId, uint8_t switch0, uint8_t switch1)
switch1(switch1), switch1(switch1),
heaterOnCountdown(10800000) /*about two orbits*/, heaterOnCountdown(10800000) /*about two orbits*/,
parameterHelper(this) { parameterHelper(this) {
eventQueue = QueueFactory::instance()->createMessageQueue(); auto mqArgs = MqArgs(objectId, static_cast<void*>(this));
eventQueue = QueueFactory::instance()->createMessageQueue(
3, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
} }
Heater::~Heater() { QueueFactory::instance()->deleteMessageQueue(eventQueue); } Heater::~Heater() { QueueFactory::instance()->deleteMessageQueue(eventQueue); }

View File

@ -33,50 +33,47 @@ class TmStoreBackendIF : public HasParametersIF {
static const ReturnValue_t INVALID_REQUEST = MAKE_RETURN_CODE(15); static const ReturnValue_t INVALID_REQUEST = MAKE_RETURN_CODE(15);
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::MEMORY; static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::MEMORY;
static const Event STORE_SEND_WRITE_FAILED = //! Initiating sending data to store failed. Low, par1:
MAKE_EVENT(0, severity::LOW); //!< Initiating sending data to store failed. Low, par1: //! returnCode, par2: integer (debug info)
//!< returnCode, par2: integer (debug info) static const Event STORE_SEND_WRITE_FAILED = MAKE_EVENT(0, severity::LOW);
static const Event STORE_WRITE_FAILED = MAKE_EVENT( //! Data was sent, but writing failed. Low, par1: returnCode, par2: 0
1, severity::LOW); //!< Data was sent, but writing failed. Low, par1: returnCode, par2: 0 static const Event STORE_WRITE_FAILED = MAKE_EVENT(1, severity::LOW);
static const Event STORE_SEND_READ_FAILED = //! Initiating reading data from store failed. Low, par1: returnCode, par2: 0
MAKE_EVENT(2, severity::LOW); //!< Initiating reading data from store failed. Low, par1: static const Event STORE_SEND_READ_FAILED = MAKE_EVENT(2, severity::LOW);
//!< returnCode, par2: 0 //! Data was requested, but access failed. Low, par1: returnCode, par2: 0
static const Event STORE_READ_FAILED = MAKE_EVENT( static const Event STORE_READ_FAILED = MAKE_EVENT(3, severity::LOW);
3, severity::LOW); //!< Data was requested, but access failed. Low, par1: returnCode, par2: 0 //! An unexpected TM packet or data message occurred. Low, par1: 0, par2: integer (debug info)
static const Event UNEXPECTED_MSG = static const Event UNEXPECTED_MSG = MAKE_EVENT(4, severity::LOW);
MAKE_EVENT(4, severity::LOW); //!< An unexpected TM packet or data message occurred. Low, //! Storing data failed. May simply be a full store. Low, par1: returnCode,
//!< par1: 0, par2: integer (debug info) //! par2: integer (sequence count of failed packet).
static const Event STORING_FAILED = MAKE_EVENT( static const Event STORING_FAILED = MAKE_EVENT(5, severity::LOW);
5, severity::LOW); //!< Storing data failed. May simply be a full store. Low, par1: //! Dumping retrieved data failed. Low, par1: returnCode,
//!< returnCode, par2: integer (sequence count of failed packet). //! par2: integer (sequence count of failed packet).
static const Event TM_DUMP_FAILED = static const Event TM_DUMP_FAILED = MAKE_EVENT(6, severity::LOW);
MAKE_EVENT(6, severity::LOW); //!< Dumping retrieved data failed. Low, par1: returnCode, //! Corrupted init data or read error. Low, par1: returnCode, par2: integer (debug info)
//!< par2: integer (sequence count of failed packet). //! Store was not initialized. Starts empty. Info, parameters both zero.
static const Event STORE_INIT_FAILED = static const Event STORE_INIT_FAILED = MAKE_EVENT(7, severity::LOW);
MAKE_EVENT(7, severity::LOW); //!< Corrupted init data or read error. Low, par1: returnCode, //! Data was read out, but it is inconsistent. Low par1:
//!< par2: integer (debug info) //! Memory address of corruption, par2: integer (debug info)
static const Event STORE_INIT_EMPTY = MAKE_EVENT( static const Event STORE_INIT_EMPTY = MAKE_EVENT(8, severity::INFO);
8, severity::INFO); //!< Store was not initialized. Starts empty. Info, parameters both zero.
static const Event STORE_CONTENT_CORRUPTED = static const Event STORE_CONTENT_CORRUPTED = MAKE_EVENT(9, severity::LOW);
MAKE_EVENT(9, severity::LOW); //!< Data was read out, but it is inconsistent. Low par1: //! Info event indicating the store will be initialized, either at boot or after IOB switch.
//!< Memory address of corruption, par2: integer (debug info) //! Info. pars: 0
static const Event STORE_INITIALIZE = static const Event STORE_INITIALIZE = MAKE_EVENT(10, severity::INFO);
MAKE_EVENT(10, severity::INFO); //!< Info event indicating the store will be initialized, //! Info event indicating the store was successfully initialized, either at boot or after
//!< either at boot or after IOB switch. Info. pars: 0 //! IOB switch. Info. pars: 0
static const Event INIT_DONE = MAKE_EVENT( static const Event INIT_DONE = MAKE_EVENT(11, severity::INFO);
11, severity::INFO); //!< Info event indicating the store was successfully initialized, //! Info event indicating that dumping finished successfully.
//!< either at boot or after IOB switch. Info. pars: 0 //! par1: Number of dumped packets. par2: APID/SSC (16bits each)
static const Event DUMP_FINISHED = MAKE_EVENT( static const Event DUMP_FINISHED = MAKE_EVENT(12, severity::INFO);
12, severity::INFO); //!< Info event indicating that dumping finished successfully. par1: //! Info event indicating that deletion finished successfully.
//!< Number of dumped packets. par2: APID/SSC (16bits each) //! par1:Number of deleted packets. par2: APID/SSC (16bits each)
static const Event DELETION_FINISHED = MAKE_EVENT( static const Event DELETION_FINISHED = MAKE_EVENT(13, severity::INFO);
13, severity::INFO); //!< Info event indicating that deletion finished successfully. par1: //! Info event indicating that something went wrong during deletion. pars: 0
//!< Number of deleted packets. par2: APID/SSC (16bits each) static const Event DELETION_FAILED = MAKE_EVENT(14, severity::LOW);
static const Event DELETION_FAILED = MAKE_EVENT( //! Info that the a auto catalog report failed
14, static const Event AUTO_CATALOGS_SENDING_FAILED = MAKE_EVENT(15, severity::INFO);
severity::LOW); //!< Info event indicating that something went wrong during deletion. pars: 0
static const Event AUTO_CATALOGS_SENDING_FAILED =
MAKE_EVENT(15, severity::INFO); //!< Info that the a auto catalog report failed
virtual ~TmStoreBackendIF() {} virtual ~TmStoreBackendIF() {}

View File

@ -20,8 +20,10 @@ CommandingServiceBase::CommandingServiceBase(object_id_t setObjectId, uint16_t a
service(service), service(service),
timeoutSeconds(commandTimeoutSeconds), timeoutSeconds(commandTimeoutSeconds),
commandMap(numberOfParallelCommands) { commandMap(numberOfParallelCommands) {
commandQueue = QueueFactory::instance()->createMessageQueue(queueDepth); auto mqArgs = MqArgs(setObjectId, static_cast<void*>(this));
requestQueue = QueueFactory::instance()->createMessageQueue(queueDepth); size_t mqSz = MessageQueueMessage::MAX_MESSAGE_SIZE;
commandQueue = QueueFactory::instance()->createMessageQueue(queueDepth, mqSz, &mqArgs);
requestQueue = QueueFactory::instance()->createMessageQueue(queueDepth, mqSz, &mqArgs);
} }
void CommandingServiceBase::setPacketSource(object_id_t packetSource) { void CommandingServiceBase::setPacketSource(object_id_t packetSource) {

View File

@ -13,7 +13,9 @@ object_id_t PusServiceBase::packetDestination = 0;
PusServiceBase::PusServiceBase(object_id_t setObjectId, uint16_t setApid, uint8_t setServiceId) PusServiceBase::PusServiceBase(object_id_t setObjectId, uint16_t setApid, uint8_t setServiceId)
: SystemObject(setObjectId), apid(setApid), serviceId(setServiceId) { : SystemObject(setObjectId), apid(setApid), serviceId(setServiceId) {
requestQueue = QueueFactory::instance()->createMessageQueue(PUS_SERVICE_MAX_RECEPTION); auto mqArgs = MqArgs(setObjectId, static_cast<void*>(this));
requestQueue = QueueFactory::instance()->createMessageQueue(
PUS_SERVICE_MAX_RECEPTION, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
} }
PusServiceBase::~PusServiceBase() { QueueFactory::instance()->deleteMessageQueue(requestQueue); } PusServiceBase::~PusServiceBase() { QueueFactory::instance()->deleteMessageQueue(requestQueue); }

View File

@ -15,7 +15,9 @@ TmTcBridge::TmTcBridge(object_id_t objectId, object_id_t tcDestination, object_i
tcDestination(tcDestination) tcDestination(tcDestination)
{ {
tmTcReceptionQueue = QueueFactory::instance()->createMessageQueue(TMTC_RECEPTION_QUEUE_DEPTH); auto mqArgs = MqArgs(objectId, static_cast<void*>(this));
tmTcReceptionQueue = QueueFactory::instance()->createMessageQueue(
TMTC_RECEPTION_QUEUE_DEPTH, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
} }
TmTcBridge::~TmTcBridge() { QueueFactory::instance()->deleteMessageQueue(tmTcReceptionQueue); } TmTcBridge::~TmTcBridge() { QueueFactory::instance()->deleteMessageQueue(tmTcReceptionQueue); }

View File

@ -3,7 +3,6 @@
#include <fsfw/objectmanager/ObjectManager.h> #include <fsfw/objectmanager/ObjectManager.h>
#include <fsfw/serviceinterface/ServiceInterface.h> #include <fsfw/serviceinterface/ServiceInterface.h>
bool TestTask::oneShotAction = true;
MutexIF* TestTask::testLock = nullptr; MutexIF* TestTask::testLock = nullptr;
TestTask::TestTask(object_id_t objectId) : SystemObject(objectId), testMode(testModes::A) { TestTask::TestTask(object_id_t objectId) : SystemObject(objectId), testMode(testModes::A) {

View File

@ -29,7 +29,7 @@ class TestTask : public SystemObject, public ExecutableObjectIF, public HasRetur
bool testFlag = false; bool testFlag = false;
private: private:
static bool oneShotAction; bool oneShotAction = true;
static MutexIF* testLock; static MutexIF* testLock;
StorageManagerIF* IPCStore; StorageManagerIF* IPCStore;
}; };