Compare commits
45 Commits
a84c770dfb
...
v2.0.0
Author | SHA1 | Date | |
---|---|---|---|
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 | |||
52b3d9473e | |||
fc9b85d5db | |||
bfae25ff2d | |||
ea3812fbbd | |||
f40f783cb4 |
@@ -26,7 +26,8 @@ enum GpioOperation {
|
||||
|
||||
enum GpioTypes {
|
||||
NONE,
|
||||
GPIO_REGULAR,
|
||||
GPIO_REGULAR_BY_CHIP,
|
||||
GPIO_REGULAR_BY_LABEL,
|
||||
CALLBACK
|
||||
};
|
||||
|
||||
@@ -68,28 +69,57 @@ public:
|
||||
int initValue = 0;
|
||||
};
|
||||
|
||||
class GpiodRegular: public GpioBase {
|
||||
class GpiodRegularBase: public GpioBase {
|
||||
public:
|
||||
GpiodRegular() :
|
||||
GpioBase(gpio::GpioTypes::GPIO_REGULAR, std::string(), gpio::Direction::IN, 0) {
|
||||
GpiodRegularBase(gpio::GpioTypes gpioType, std::string consumer, gpio::Direction direction,
|
||||
int initValue, int lineNum): GpioBase(gpioType, consumer, direction, initValue),
|
||||
lineNum(lineNum) {
|
||||
}
|
||||
;
|
||||
|
||||
GpiodRegular(std::string chipname_, int lineNum_, std::string consumer_,
|
||||
gpio::Direction direction_, int initValue_) :
|
||||
GpioBase(gpio::GpioTypes::GPIO_REGULAR, consumer_, direction_, initValue_),
|
||||
chipname(chipname_), lineNum(lineNum_) {
|
||||
}
|
||||
|
||||
GpiodRegular(std::string chipname_, int lineNum_, std::string consumer_) :
|
||||
GpioBase(gpio::GpioTypes::GPIO_REGULAR, consumer_, gpio::Direction::IN, 0),
|
||||
chipname(chipname_), lineNum(lineNum_) {
|
||||
}
|
||||
std::string chipname;
|
||||
int lineNum = 0;
|
||||
struct gpiod_line* lineHandle = nullptr;
|
||||
};
|
||||
|
||||
class GpiodRegularByChip: public GpiodRegularBase {
|
||||
public:
|
||||
GpiodRegularByChip() :
|
||||
GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP,
|
||||
std::string(), gpio::Direction::IN, gpio::LOW, 0) {
|
||||
}
|
||||
|
||||
GpiodRegularByChip(std::string chipname_, int lineNum_, std::string consumer_,
|
||||
gpio::Direction direction_, int initValue_) :
|
||||
GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP,
|
||||
consumer_, direction_, initValue_, lineNum_),
|
||||
chipname(chipname_){
|
||||
}
|
||||
|
||||
GpiodRegularByChip(std::string chipname_, int lineNum_, std::string consumer_) :
|
||||
GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP, consumer_,
|
||||
gpio::Direction::IN, gpio::LOW, lineNum_),
|
||||
chipname(chipname_) {
|
||||
}
|
||||
|
||||
std::string chipname;
|
||||
};
|
||||
|
||||
class GpiodRegularByLabel: public GpiodRegularBase {
|
||||
public:
|
||||
GpiodRegularByLabel(std::string label_, int lineNum_, std::string consumer_,
|
||||
gpio::Direction direction_, int initValue_) :
|
||||
GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL, consumer_,
|
||||
direction_, initValue_, lineNum_),
|
||||
label(label_) {
|
||||
}
|
||||
|
||||
GpiodRegularByLabel(std::string label_, int lineNum_, std::string consumer_) :
|
||||
GpiodRegularBase(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL, consumer_,
|
||||
gpio::Direction::IN, gpio::LOW, lineNum_),
|
||||
label(label_) {
|
||||
}
|
||||
|
||||
std::string label;
|
||||
};
|
||||
|
||||
class GpioCallback: public GpioBase {
|
||||
public:
|
||||
GpioCallback(std::string consumer, gpio::Direction direction_, int initValue_,
|
||||
|
@@ -2,7 +2,6 @@
|
||||
#define MISSION_DEVICES_MGMRM3100HANDLER_H_
|
||||
|
||||
#include "fsfw/FSFW.h"
|
||||
#include "devices/powerSwitcherList.h"
|
||||
#include "devicedefinitions/MgmRM3100HandlerDefs.h"
|
||||
#include "fsfw/devicehandlers/DeviceHandlerBase.h"
|
||||
|
||||
|
@@ -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 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 REVID_REGISTER = 0x36;
|
||||
|
||||
|
@@ -20,7 +20,7 @@ LinuxLibgpioIF::~LinuxLibgpioIF() {
|
||||
ReturnValue_t LinuxLibgpioIF::addGpios(GpioCookie* gpioCookie) {
|
||||
ReturnValue_t result;
|
||||
if(gpioCookie == nullptr) {
|
||||
sif::error << "LinuxLibgpioIF::initialize: Invalid cookie" << std::endl;
|
||||
sif::error << "LinuxLibgpioIF::addGpios: Invalid cookie" << std::endl;
|
||||
return RETURN_FAILED;
|
||||
}
|
||||
|
||||
@@ -45,16 +45,25 @@ ReturnValue_t LinuxLibgpioIF::addGpios(GpioCookie* gpioCookie) {
|
||||
|
||||
ReturnValue_t LinuxLibgpioIF::configureGpios(GpioMap& mapToAdd) {
|
||||
for(auto& gpioConfig: mapToAdd) {
|
||||
switch(gpioConfig.second->gpioType) {
|
||||
auto& gpioType = gpioConfig.second->gpioType;
|
||||
switch(gpioType) {
|
||||
case(gpio::GpioTypes::NONE): {
|
||||
return GPIO_INVALID_INSTANCE;
|
||||
}
|
||||
case(gpio::GpioTypes::GPIO_REGULAR): {
|
||||
GpiodRegular* regularGpio = dynamic_cast<GpiodRegular*>(gpioConfig.second);
|
||||
case(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP): {
|
||||
auto regularGpio = dynamic_cast<GpiodRegularByChip*>(gpioConfig.second);
|
||||
if(regularGpio == nullptr) {
|
||||
return GPIO_INVALID_INSTANCE;
|
||||
}
|
||||
configureRegularGpio(gpioConfig.first, regularGpio);
|
||||
configureGpioByChip(gpioConfig.first, *regularGpio);
|
||||
break;
|
||||
}
|
||||
case(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL):{
|
||||
auto regularGpio = dynamic_cast<GpiodRegularByLabel*>(gpioConfig.second);
|
||||
if(regularGpio == nullptr) {
|
||||
return GPIO_INVALID_INSTANCE;
|
||||
}
|
||||
configureGpioByLabel(gpioConfig.first, *regularGpio);
|
||||
break;
|
||||
}
|
||||
case(gpio::GpioTypes::CALLBACK): {
|
||||
@@ -70,41 +79,59 @@ ReturnValue_t LinuxLibgpioIF::configureGpios(GpioMap& mapToAdd) {
|
||||
return RETURN_OK;
|
||||
}
|
||||
|
||||
ReturnValue_t LinuxLibgpioIF::configureRegularGpio(gpioId_t gpioId, GpiodRegular *regularGpio) {
|
||||
std::string chipname;
|
||||
ReturnValue_t LinuxLibgpioIF::configureGpioByLabel(gpioId_t gpioId,
|
||||
GpiodRegularByLabel &gpioByLabel) {
|
||||
std::string& label = gpioByLabel.label;
|
||||
struct gpiod_chip* chip = gpiod_chip_open_by_label(label.c_str());
|
||||
if (chip == nullptr) {
|
||||
sif::warning << "LinuxLibgpioIF::configureRegularGpio: Failed to open gpio from gpio "
|
||||
<< "group with label " << label << ". Gpio ID: " << gpioId << std::endl;
|
||||
return RETURN_FAILED;
|
||||
|
||||
}
|
||||
std::string failOutput = "label: " + label;
|
||||
return configureRegularGpio(gpioId, gpioByLabel.gpioType, chip, gpioByLabel, failOutput);
|
||||
}
|
||||
|
||||
ReturnValue_t LinuxLibgpioIF::configureGpioByChip(gpioId_t gpioId,
|
||||
GpiodRegularByChip &gpioByChip) {
|
||||
std::string& chipname = gpioByChip.chipname;
|
||||
struct gpiod_chip* chip = gpiod_chip_open_by_name(chipname.c_str());
|
||||
if (chip == nullptr) {
|
||||
sif::warning << "LinuxLibgpioIF::configureRegularGpio: Failed to open chip "
|
||||
<< chipname << ". Gpio ID: " << gpioId << std::endl;
|
||||
return RETURN_FAILED;
|
||||
}
|
||||
std::string failOutput = "chipname: " + chipname;
|
||||
return configureRegularGpio(gpioId, gpioByChip.gpioType, chip, gpioByChip, failOutput);
|
||||
}
|
||||
|
||||
ReturnValue_t LinuxLibgpioIF::configureRegularGpio(gpioId_t gpioId, gpio::GpioTypes gpioType,
|
||||
struct gpiod_chip* chip, GpiodRegularBase& regularGpio, std::string failOutput) {
|
||||
unsigned int lineNum;
|
||||
struct gpiod_chip *chip;
|
||||
gpio::Direction direction;
|
||||
std::string consumer;
|
||||
struct gpiod_line *lineHandle;
|
||||
int result = 0;
|
||||
|
||||
chipname = regularGpio->chipname;
|
||||
chip = gpiod_chip_open_by_name(chipname.c_str());
|
||||
if (!chip) {
|
||||
sif::warning << "LinuxLibgpioIF::configureRegularGpio: Failed to open chip "
|
||||
<< chipname << ". Gpio ID: " << gpioId << std::endl;
|
||||
return RETURN_FAILED;
|
||||
}
|
||||
|
||||
lineNum = regularGpio->lineNum;
|
||||
lineNum = regularGpio.lineNum;
|
||||
lineHandle = gpiod_chip_get_line(chip, lineNum);
|
||||
if (!lineHandle) {
|
||||
sif::debug << "LinuxLibgpioIF::configureRegularGpio: Failed to open line " << std::endl;
|
||||
sif::debug << "GPIO ID: " << gpioId << ", line number: " << lineNum <<
|
||||
", chipname: " << chipname << std::endl;
|
||||
sif::debug << "Check if linux GPIO configuration has changed. " << std::endl;
|
||||
sif::warning << "LinuxLibgpioIF::configureRegularGpio: Failed to open line " << std::endl;
|
||||
sif::warning << "GPIO ID: " << gpioId << ", line number: " << lineNum <<
|
||||
", " << failOutput << std::endl;
|
||||
sif::warning << "Check if Linux GPIO configuration has changed. " << std::endl;
|
||||
gpiod_chip_close(chip);
|
||||
return RETURN_FAILED;
|
||||
}
|
||||
|
||||
direction = regularGpio->direction;
|
||||
consumer = regularGpio->consumer;
|
||||
direction = regularGpio.direction;
|
||||
consumer = regularGpio.consumer;
|
||||
/* Configure direction and add a description to the GPIO */
|
||||
switch (direction) {
|
||||
case(gpio::OUT): {
|
||||
result = gpiod_line_request_output(lineHandle, consumer.c_str(),
|
||||
regularGpio->initValue);
|
||||
regularGpio.initValue);
|
||||
if (result < 0) {
|
||||
sif::error << "LinuxLibgpioIF::configureRegularGpio: Failed to request line " << lineNum <<
|
||||
" from GPIO instance with ID: " << gpioId << std::endl;
|
||||
@@ -134,7 +161,7 @@ ReturnValue_t LinuxLibgpioIF::configureRegularGpio(gpioId_t gpioId, GpiodRegular
|
||||
* Write line handle to GPIO configuration instance so it can later be used to set or
|
||||
* read states of GPIOs.
|
||||
*/
|
||||
regularGpio->lineHandle = lineHandle;
|
||||
regularGpio.lineHandle = lineHandle;
|
||||
return RETURN_OK;
|
||||
}
|
||||
|
||||
@@ -145,8 +172,14 @@ ReturnValue_t LinuxLibgpioIF::pullHigh(gpioId_t gpioId) {
|
||||
return UNKNOWN_GPIO_ID;
|
||||
}
|
||||
|
||||
if(gpioMapIter->second->gpioType == gpio::GpioTypes::GPIO_REGULAR) {
|
||||
return driveGpio(gpioId, dynamic_cast<GpiodRegular*>(gpioMapIter->second), 1);
|
||||
auto gpioType = gpioMapIter->second->gpioType;
|
||||
if(gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_CHIP or
|
||||
gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LABEL) {
|
||||
auto regularGpio = dynamic_cast<GpiodRegularBase*>(gpioMapIter->second);
|
||||
if(regularGpio == nullptr) {
|
||||
return GPIO_TYPE_FAILURE;
|
||||
}
|
||||
return driveGpio(gpioId, *regularGpio, gpio::HIGH);
|
||||
}
|
||||
else {
|
||||
auto gpioCallback = dynamic_cast<GpioCallback*>(gpioMapIter->second);
|
||||
@@ -167,8 +200,14 @@ ReturnValue_t LinuxLibgpioIF::pullLow(gpioId_t gpioId) {
|
||||
return UNKNOWN_GPIO_ID;
|
||||
}
|
||||
|
||||
if(gpioMapIter->second->gpioType == gpio::GpioTypes::GPIO_REGULAR) {
|
||||
return driveGpio(gpioId, dynamic_cast<GpiodRegular*>(gpioMapIter->second), 0);
|
||||
auto& gpioType = gpioMapIter->second->gpioType;
|
||||
if(gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_CHIP or
|
||||
gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LABEL) {
|
||||
auto regularGpio = dynamic_cast<GpiodRegularBase*>(gpioMapIter->second);
|
||||
if(regularGpio == nullptr) {
|
||||
return GPIO_TYPE_FAILURE;
|
||||
}
|
||||
return driveGpio(gpioId, *regularGpio, gpio::LOW);
|
||||
}
|
||||
else {
|
||||
auto gpioCallback = dynamic_cast<GpioCallback*>(gpioMapIter->second);
|
||||
@@ -183,12 +222,8 @@ ReturnValue_t LinuxLibgpioIF::pullLow(gpioId_t gpioId) {
|
||||
}
|
||||
|
||||
ReturnValue_t LinuxLibgpioIF::driveGpio(gpioId_t gpioId,
|
||||
GpiodRegular* regularGpio, unsigned int logicLevel) {
|
||||
if(regularGpio == nullptr) {
|
||||
return GPIO_TYPE_FAILURE;
|
||||
}
|
||||
|
||||
int result = gpiod_line_set_value(regularGpio->lineHandle, logicLevel);
|
||||
GpiodRegularBase& regularGpio, gpio::Levels logicLevel) {
|
||||
int result = gpiod_line_set_value(regularGpio.lineHandle, logicLevel);
|
||||
if (result < 0) {
|
||||
sif::warning << "LinuxLibgpioIF::driveGpio: Failed to pull GPIO with ID " << gpioId <<
|
||||
" to logic level " << logicLevel << std::endl;
|
||||
@@ -204,9 +239,10 @@ ReturnValue_t LinuxLibgpioIF::readGpio(gpioId_t gpioId, int* gpioState) {
|
||||
sif::warning << "LinuxLibgpioIF::readGpio: Unknown GPIOD ID " << gpioId << std::endl;
|
||||
return UNKNOWN_GPIO_ID;
|
||||
}
|
||||
|
||||
if(gpioMapIter->second->gpioType == gpio::GpioTypes::GPIO_REGULAR) {
|
||||
GpiodRegular* regularGpio = dynamic_cast<GpiodRegular*>(gpioMapIter->second);
|
||||
auto gpioType = gpioMapIter->second->gpioType;
|
||||
if(gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_CHIP or
|
||||
gpioType == gpio::GpioTypes::GPIO_REGULAR_BY_LABEL) {
|
||||
auto regularGpio = dynamic_cast<GpiodRegularBase*>(gpioMapIter->second);
|
||||
if(regularGpio == nullptr) {
|
||||
return GPIO_TYPE_FAILURE;
|
||||
}
|
||||
@@ -225,13 +261,14 @@ ReturnValue_t LinuxLibgpioIF::checkForConflicts(GpioMap& mapToAdd){
|
||||
ReturnValue_t result = HasReturnvaluesIF::RETURN_OK;
|
||||
for(auto& gpioConfig: mapToAdd) {
|
||||
switch(gpioConfig.second->gpioType) {
|
||||
case(gpio::GpioTypes::GPIO_REGULAR): {
|
||||
auto regularGpio = dynamic_cast<GpiodRegular*>(gpioConfig.second);
|
||||
case(gpio::GpioTypes::GPIO_REGULAR_BY_CHIP):
|
||||
case(gpio::GpioTypes::GPIO_REGULAR_BY_LABEL): {
|
||||
auto regularGpio = dynamic_cast<GpiodRegularBase*>(gpioConfig.second);
|
||||
if(regularGpio == nullptr) {
|
||||
return GPIO_TYPE_FAILURE;
|
||||
}
|
||||
/* Check for conflicts and remove duplicates if necessary */
|
||||
result = checkForConflictsRegularGpio(gpioConfig.first, regularGpio, mapToAdd);
|
||||
result = checkForConflictsRegularGpio(gpioConfig.first, *regularGpio, mapToAdd);
|
||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
||||
status = result;
|
||||
}
|
||||
@@ -259,17 +296,19 @@ ReturnValue_t LinuxLibgpioIF::checkForConflicts(GpioMap& mapToAdd){
|
||||
|
||||
|
||||
ReturnValue_t LinuxLibgpioIF::checkForConflictsRegularGpio(gpioId_t gpioIdToCheck,
|
||||
GpiodRegular* gpioToCheck, GpioMap& mapToAdd) {
|
||||
GpiodRegularBase& gpioToCheck, GpioMap& mapToAdd) {
|
||||
/* Cross check with private map */
|
||||
gpioMapIter = gpioMap.find(gpioIdToCheck);
|
||||
if(gpioMapIter != gpioMap.end()) {
|
||||
if(gpioMapIter->second->gpioType != gpio::GpioTypes::GPIO_REGULAR) {
|
||||
auto& gpioType = gpioMapIter->second->gpioType;
|
||||
if(gpioType != gpio::GpioTypes::GPIO_REGULAR_BY_CHIP and
|
||||
gpioType != gpio::GpioTypes::GPIO_REGULAR_BY_LABEL) {
|
||||
sif::warning << "LinuxLibgpioIF::checkForConflicts: ID already exists for different "
|
||||
"GPIO type" << gpioIdToCheck << ". Removing duplicate." << std::endl;
|
||||
mapToAdd.erase(gpioIdToCheck);
|
||||
return HasReturnvaluesIF::RETURN_OK;
|
||||
}
|
||||
auto ownRegularGpio = dynamic_cast<GpiodRegular*>(gpioMapIter->second);
|
||||
auto ownRegularGpio = dynamic_cast<GpiodRegularBase*>(gpioMapIter->second);
|
||||
if(ownRegularGpio == nullptr) {
|
||||
return GPIO_TYPE_FAILURE;
|
||||
}
|
||||
|
@@ -6,6 +6,7 @@
|
||||
#include <fsfw/objectmanager/SystemObject.h>
|
||||
|
||||
class GpioCookie;
|
||||
class GpiodRegularIF;
|
||||
|
||||
/**
|
||||
* @brief This class implements the GpioIF for a linux based system. The
|
||||
@@ -47,9 +48,13 @@ private:
|
||||
* @param gpioId The GPIO ID of the GPIO to drive.
|
||||
* @param logiclevel The logic level to set. O or 1.
|
||||
*/
|
||||
ReturnValue_t driveGpio(gpioId_t gpioId, GpiodRegular* regularGpio, unsigned int logiclevel);
|
||||
ReturnValue_t driveGpio(gpioId_t gpioId, GpiodRegularBase& regularGpio,
|
||||
gpio::Levels logicLevel);
|
||||
|
||||
ReturnValue_t configureRegularGpio(gpioId_t gpioId, GpiodRegular* regularGpio);
|
||||
ReturnValue_t configureGpioByLabel(gpioId_t gpioId, GpiodRegularByLabel& gpioByLabel);
|
||||
ReturnValue_t configureGpioByChip(gpioId_t gpioId, GpiodRegularByChip& gpioByChip);
|
||||
ReturnValue_t configureRegularGpio(gpioId_t gpioId, gpio::GpioTypes gpioType,
|
||||
struct gpiod_chip* chip, GpiodRegularBase& regularGpio, std::string failOutput);
|
||||
|
||||
/**
|
||||
* @brief This function checks if GPIOs are already registered and whether
|
||||
@@ -62,7 +67,7 @@ private:
|
||||
*/
|
||||
ReturnValue_t checkForConflicts(GpioMap& mapToAdd);
|
||||
|
||||
ReturnValue_t checkForConflictsRegularGpio(gpioId_t gpiodId, GpiodRegular* regularGpio,
|
||||
ReturnValue_t checkForConflictsRegularGpio(gpioId_t gpiodId, GpiodRegularBase& regularGpio,
|
||||
GpioMap& mapToAdd);
|
||||
ReturnValue_t checkForConflictsCallbackGpio(gpioId_t gpiodId, GpioCallback* regularGpio,
|
||||
GpioMap& mapToAdd);
|
||||
|
@@ -12,7 +12,7 @@ ReturnValue_t gpio::createRpiGpioConfig(GpioCookie* cookie, gpioId_t gpioId, int
|
||||
return HasReturnvaluesIF::RETURN_FAILED;
|
||||
}
|
||||
|
||||
GpiodRegular* config = new GpiodRegular();
|
||||
auto config = new GpiodRegularByChip();
|
||||
/* Default chipname for Raspberry Pi. There is still gpiochip1 for expansion, but most users
|
||||
will not need this */
|
||||
config->chipname = "gpiochip0";
|
||||
|
@@ -141,8 +141,8 @@ ReturnValue_t SpiComIF::sendMessage(CookieIF *cookie, const uint8_t *sendData, s
|
||||
if(sendLen > spiCookie->getMaxBufferSize()) {
|
||||
#if FSFW_VERBOSE_LEVEL >= 1
|
||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||
sif::warning << "SpiComIF::sendMessage: Too much data sent, send length" << sendLen <<
|
||||
"larger than maximum buffer length" << spiCookie->getMaxBufferSize() << std::endl;
|
||||
sif::warning << "SpiComIF::sendMessage: Too much data sent, send length " << sendLen <<
|
||||
"larger than maximum buffer length " << spiCookie->getMaxBufferSize() << std::endl;
|
||||
#else
|
||||
sif::printWarning("SpiComIF::sendMessage: Too much data sent, send length %lu larger "
|
||||
"than maximum buffer length %lu!\n", static_cast<unsigned long>(sendLen),
|
||||
@@ -197,12 +197,26 @@ ReturnValue_t SpiComIF::performRegularSendOperation(SpiCookie *spiCookie, const
|
||||
if(gpioId != gpio::NO_GPIO) {
|
||||
result = spiMutex->lockMutex(timeoutType, timeoutMs);
|
||||
if (result != RETURN_OK) {
|
||||
#if FSFW_VERBOSE_LEVEL >= 1
|
||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||
sif::error << "SpiComIF::sendMessage: Failed to lock mutex" << std::endl;
|
||||
#else
|
||||
sif::printError("SpiComIF::sendMessage: Failed to lock mutex\n");
|
||||
#endif
|
||||
#endif
|
||||
return result;
|
||||
}
|
||||
ReturnValue_t result = gpioComIF->pullLow(gpioId);
|
||||
if(result != HasReturnvaluesIF::RETURN_OK) {
|
||||
#if FSFW_VERBOSE_LEVEL >= 1
|
||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||
sif::warning << "SpiComIF::sendMessage: Pulling low CS pin failed" << std::endl;
|
||||
#else
|
||||
sif::printWarning("SpiComIF::sendMessage: Pulling low CS pin failed");
|
||||
#endif
|
||||
#endif
|
||||
return result;
|
||||
}
|
||||
gpioComIF->pullLow(gpioId);
|
||||
}
|
||||
|
||||
/* Execute transfer */
|
||||
@@ -213,7 +227,7 @@ ReturnValue_t SpiComIF::performRegularSendOperation(SpiCookie *spiCookie, const
|
||||
utility::handleIoctlError("SpiComIF::sendMessage: ioctl error.");
|
||||
result = FULL_DUPLEX_TRANSFER_FAILED;
|
||||
}
|
||||
#if FSFW_HAL_LINUX_SPI_WIRETAPPING == 1
|
||||
#if FSFW_HAL_SPI_WIRETAPPING == 1
|
||||
performSpiWiretapping(spiCookie);
|
||||
#endif /* FSFW_LINUX_SPI_WIRETAPPING == 1 */
|
||||
}
|
||||
@@ -384,11 +398,11 @@ GpioIF* SpiComIF::getGpioInterface() {
|
||||
void SpiComIF::setSpiSpeedAndMode(int spiFd, spi::SpiModes mode, uint32_t speed) {
|
||||
int retval = ioctl(spiFd, SPI_IOC_WR_MODE, reinterpret_cast<uint8_t*>(&mode));
|
||||
if(retval != 0) {
|
||||
utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI mode failed!");
|
||||
utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Setting SPI mode failed");
|
||||
}
|
||||
|
||||
retval = ioctl(spiFd, SPI_IOC_WR_MAX_SPEED_HZ, &speed);
|
||||
if(retval != 0) {
|
||||
utility::handleIoctlError("SpiTestClass::performRm3100Test: Setting SPI speed failed!");
|
||||
utility::handleIoctlError("SpiComIF::setSpiSpeedAndMode: Setting SPI speed failed");
|
||||
}
|
||||
}
|
||||
|
@@ -16,6 +16,11 @@
|
||||
#cmakedefine FSFW_ADD_MONITORING
|
||||
#cmakedefine FSFW_ADD_SGP4_PROPAGATOR
|
||||
|
||||
// Can be used for low-level debugging of the SPI bus
|
||||
#ifndef FSFW_HAL_SPI_WIRETAPPING
|
||||
#define FSFW_HAL_SPI_WIRETAPPING 0
|
||||
#endif
|
||||
|
||||
#ifndef FSFW_HAL_L3GD20_GYRO_DEBUG
|
||||
#define FSFW_HAL_L3GD20_GYRO_DEBUG 0
|
||||
#endif /* FSFW_HAL_L3GD20_GYRO_DEBUG */
|
||||
|
@@ -3,8 +3,8 @@
|
||||
|
||||
const char* const FSFW_VERSION_NAME = "ASTP";
|
||||
|
||||
#define FSFW_VERSION 1
|
||||
#define FSFW_SUBVERSION 2
|
||||
#define FSFW_VERSION 2
|
||||
#define FSFW_SUBVERSION 0
|
||||
#define FSFW_REVISION 0
|
||||
|
||||
#endif /* FSFW_VERSION_H_ */
|
||||
|
@@ -165,11 +165,9 @@ ReturnValue_t DleEncoder::decodeStreamEscaped(const uint8_t *sourceStream, size_
|
||||
if (sourceStream[encodedIndex++] != STX_CHAR) {
|
||||
return DECODING_ERROR;
|
||||
}
|
||||
while ((encodedIndex < sourceStreamLen)
|
||||
and (decodedIndex < maxDestStreamlen)
|
||||
and (sourceStream[encodedIndex] != ETX_CHAR)
|
||||
and (sourceStream[encodedIndex] != STX_CHAR)) {
|
||||
if (sourceStream[encodedIndex] == DLE_CHAR) {
|
||||
while ((encodedIndex < sourceStreamLen) and (decodedIndex < maxDestStreamlen)) {
|
||||
switch(sourceStream[encodedIndex]) {
|
||||
case(DLE_CHAR): {
|
||||
if(encodedIndex + 1 >= sourceStreamLen) {
|
||||
//reached the end of the sourceStream
|
||||
*readLen = sourceStreamLen;
|
||||
@@ -197,29 +195,33 @@ ReturnValue_t DleEncoder::decodeStreamEscaped(const uint8_t *sourceStream, size_
|
||||
}
|
||||
}
|
||||
++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];
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
++encodedIndex;
|
||||
++decodedIndex;
|
||||
}
|
||||
if (sourceStream[encodedIndex] != ETX_CHAR) {
|
||||
if(decodedIndex == maxDestStreamlen) {
|
||||
//so far we did not find anything wrong here, so let user try again
|
||||
*readLen = 0;
|
||||
return STREAM_TOO_SHORT;
|
||||
}
|
||||
else {
|
||||
*readLen = ++encodedIndex;
|
||||
return DECODING_ERROR;
|
||||
}
|
||||
}
|
||||
else {
|
||||
*readLen = ++encodedIndex;
|
||||
*decodedLen = decodedIndex;
|
||||
return RETURN_OK;
|
||||
|
||||
if(decodedIndex == maxDestStreamlen) {
|
||||
//so far we did not find anything wrong here, so let user try again
|
||||
*readLen = 0;
|
||||
return STREAM_TOO_SHORT;
|
||||
} else {
|
||||
*readLen = encodedIndex;
|
||||
return DECODING_ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
|
@@ -13,7 +13,6 @@ target_sources(${LIB_FSFW_NAME}
|
||||
QueueFactory.cpp
|
||||
SemaphoreFactory.cpp
|
||||
TaskFactory.cpp
|
||||
Timer.cpp
|
||||
tcpipHelpers.cpp
|
||||
unixUtility.cpp
|
||||
)
|
||||
|
@@ -1,45 +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;
|
||||
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;
|
||||
}
|
@@ -1,45 +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);
|
||||
|
||||
private:
|
||||
timer_t timerId;
|
||||
};
|
||||
|
||||
#endif /* FRAMEWORK_OSAL_LINUX_TIMER_H_ */
|
@@ -72,10 +72,12 @@ enum: uint8_t {
|
||||
PUS_SERVICE_3, //PUS3
|
||||
PUS_SERVICE_9, //PUS9
|
||||
FILE_SYSTEM, //FILS
|
||||
LINUX_OSAL, //UXOS
|
||||
HAL_SPI, //HSPI
|
||||
HAL_UART, //HURT
|
||||
HAL_I2C, //HI2C
|
||||
HAL_GPIO, //HGIO
|
||||
FIXED_SLOT_TASK_IF, //FTIF
|
||||
MGM_LIS3MDL, //MGMLIS3
|
||||
MGM_RM3100, //MGMRM3100
|
||||
FW_CLASS_ID_COUNT // [EXPORT] : [END]
|
||||
|
@@ -1,4 +1,5 @@
|
||||
#include "fsfw/tasks/FixedSlotSequence.h"
|
||||
#include "fsfw/tasks/FixedTimeslotTaskIF.h"
|
||||
#include "fsfw/serviceinterface/ServiceInterface.h"
|
||||
#include <cstdlib>
|
||||
|
||||
@@ -92,10 +93,9 @@ void FixedSlotSequence::addSlot(object_id_t componentId, uint32_t slotTimeMs,
|
||||
ReturnValue_t FixedSlotSequence::checkSequence() const {
|
||||
if(slotList.empty()) {
|
||||
#if FSFW_CPP_OSTREAM_ENABLED == 1
|
||||
sif::error << "FixedSlotSequence::checkSequence:"
|
||||
<< " Slot list is empty!" << std::endl;
|
||||
sif::warning << "FixedSlotSequence::checkSequence: Slot list is empty!" << std::endl;
|
||||
#endif
|
||||
return HasReturnvaluesIF::RETURN_FAILED;
|
||||
return FixedTimeslotTaskIF::SLOT_LIST_EMPTY;
|
||||
}
|
||||
|
||||
if(customCheckFunction != nullptr) {
|
||||
|
@@ -2,7 +2,7 @@
|
||||
#define FSFW_TASKS_FIXEDSLOTSEQUENCE_H_
|
||||
|
||||
#include "FixedSequenceSlot.h"
|
||||
#include "../objectmanager/SystemObject.h"
|
||||
#include "fsfw/objectmanager/SystemObject.h"
|
||||
|
||||
#include <set>
|
||||
|
||||
@@ -136,6 +136,7 @@ public:
|
||||
* @details
|
||||
* Checks if timing is ok (must be ascending) and if all handlers were found.
|
||||
* @return
|
||||
* - SLOT_LIST_EMPTY if the slot list is empty
|
||||
*/
|
||||
ReturnValue_t checkSequence() const;
|
||||
|
||||
@@ -147,6 +148,7 @@ public:
|
||||
* The general check will be continued for now if the custom check function
|
||||
* fails but a diagnostic debug output will be given.
|
||||
* @param customCheckFunction
|
||||
*
|
||||
*/
|
||||
void addCustomCheck(ReturnValue_t (*customCheckFunction)(const SlotList &));
|
||||
|
||||
|
@@ -2,7 +2,8 @@
|
||||
#define FRAMEWORK_TASKS_FIXEDTIMESLOTTASKIF_H_
|
||||
|
||||
#include "PeriodicTaskIF.h"
|
||||
#include "../objectmanager/ObjectManagerIF.h"
|
||||
#include "fsfw/objectmanager/ObjectManagerIF.h"
|
||||
#include "fsfw/returnvalues/FwClassIds.h"
|
||||
|
||||
/**
|
||||
* @brief Following the same principle as the base class IF.
|
||||
@@ -12,6 +13,8 @@ class FixedTimeslotTaskIF : public PeriodicTaskIF {
|
||||
public:
|
||||
virtual ~FixedTimeslotTaskIF() {}
|
||||
|
||||
static constexpr ReturnValue_t SLOT_LIST_EMPTY = HasReturnvaluesIF::makeReturnCode(
|
||||
CLASS_ID::FIXED_SLOT_TASK_IF, 0);
|
||||
/**
|
||||
* Add an object with a slot time and the execution step to the task.
|
||||
* The execution step will be passed to the object (e.g. as an operation
|
||||
|
@@ -1,5 +1,8 @@
|
||||
#ifndef FRAMEWORK_TASKS_TYPEDEF_H_
|
||||
#define FRAMEWORK_TASKS_TYPEDEF_H_
|
||||
#ifndef FSFW_TASKS_TYPEDEF_H_
|
||||
#define FSFW_TASKS_TYPEDEF_H_
|
||||
|
||||
#include <cstdint>
|
||||
#include <cstddef>
|
||||
|
||||
typedef const char* TaskName;
|
||||
typedef uint32_t TaskPriority;
|
||||
@@ -7,4 +10,4 @@ typedef size_t TaskStackSize;
|
||||
typedef double TaskPeriod;
|
||||
typedef void (*TaskDeadlineMissedFunction)();
|
||||
|
||||
#endif /* FRAMEWORK_TASKS_TYPEDEF_H_ */
|
||||
#endif /* FSFW_TASKS_TYPEDEF_H_ */
|
||||
|
@@ -6,16 +6,14 @@ Countdown::Countdown(uint32_t initialTimeout): timeout(initialTimeout) {
|
||||
Countdown::~Countdown() {
|
||||
}
|
||||
|
||||
ReturnValue_t Countdown::setTimeout(uint32_t miliseconds) {
|
||||
ReturnValue_t return_value = Clock::getUptime( &startTime );
|
||||
timeout = miliseconds;
|
||||
return return_value;
|
||||
ReturnValue_t Countdown::setTimeout(uint32_t milliseconds) {
|
||||
ReturnValue_t returnValue = Clock::getUptime( &startTime );
|
||||
timeout = milliseconds;
|
||||
return returnValue;
|
||||
}
|
||||
|
||||
bool Countdown::hasTimedOut() const {
|
||||
uint32_t current_time;
|
||||
Clock::getUptime( ¤t_time );
|
||||
if ( uint32_t(current_time - startTime) >= timeout) {
|
||||
if ( uint32_t( this->getCurrentTime() - startTime) >= timeout) {
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
@@ -31,7 +29,23 @@ ReturnValue_t Countdown::resetTimer() {
|
||||
}
|
||||
|
||||
void Countdown::timeOut() {
|
||||
uint32_t current_time;
|
||||
Clock::getUptime( ¤t_time );
|
||||
startTime= current_time - timeout;
|
||||
startTime = this->getCurrentTime() - 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"
|
||||
|
||||
/**
|
||||
* @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 {
|
||||
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();
|
||||
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;
|
||||
|
||||
/**
|
||||
* Complementary to hasTimedOut.
|
||||
*
|
||||
* @return True if the countdown is till running
|
||||
* False if it is still running
|
||||
*/
|
||||
bool isBusy() const;
|
||||
|
||||
//!< Use last set timeout value and restart timer.
|
||||
/**
|
||||
* Uses last set timeout value and restarts timer.
|
||||
*/
|
||||
ReturnValue_t resetTimer();
|
||||
|
||||
//!< Make hasTimedOut() return true
|
||||
/**
|
||||
* Returns the remaining milliseconds (0 if timeout)
|
||||
*/
|
||||
uint32_t getRemainingMillis() const;
|
||||
/**
|
||||
* Makes hasTimedOut() return true
|
||||
*/
|
||||
void timeOut();
|
||||
|
||||
/**
|
||||
* Internal countdown duration in milliseconds
|
||||
*/
|
||||
uint32_t timeout;
|
||||
private:
|
||||
/**
|
||||
* Last time the timer was started (uptime)
|
||||
*/
|
||||
uint32_t startTime = 0;
|
||||
|
||||
uint32_t getCurrentTime() const;
|
||||
};
|
||||
|
||||
#endif /* FSFW_TIMEMANAGER_COUNTDOWN_H_ */
|
||||
|
@@ -19,7 +19,7 @@ class TmTcBridge : public AcceptsTelemetryIF,
|
||||
public:
|
||||
static constexpr uint8_t TMTC_RECEPTION_QUEUE_DEPTH = 20;
|
||||
static constexpr uint8_t LIMIT_STORED_DATA_SENT_PER_CYCLE = 15;
|
||||
static constexpr uint8_t LIMIT_DOWNLINK_PACKETS_STORED = 20;
|
||||
static constexpr uint8_t LIMIT_DOWNLINK_PACKETS_STORED = 200;
|
||||
|
||||
static constexpr uint8_t DEFAULT_STORED_DATA_SENT_PER_CYCLE = 5;
|
||||
static constexpr uint8_t DEFAULT_DOWNLINK_PACKETS_STORED = 10;
|
||||
|
@@ -18,4 +18,5 @@ add_subdirectory(serialize)
|
||||
add_subdirectory(datapoollocal)
|
||||
add_subdirectory(storagemanager)
|
||||
add_subdirectory(globalfunctions)
|
||||
add_subdirectory(timemanager)
|
||||
add_subdirectory(tmtcpacket)
|
||||
|
@@ -103,7 +103,7 @@ TEST_CASE("DleEncoder" , "[DleEncoder]") {
|
||||
for(size_t faultyDestSize = 0; faultyDestSize < expectedVec.size(); faultyDestSize ++) {
|
||||
result = dleEncoder.encode(vecToEncode.data(), vecToEncode.size(),
|
||||
buffer.data(), faultyDestSize, &encodedLen);
|
||||
REQUIRE(result == DleEncoder::STREAM_TOO_SHORT);
|
||||
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));
|
||||
|
||||
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