Merge remote-tracking branch 'eive/develop' into use-eive-upstream

This commit is contained in:
Robin Müller 2023-06-30 15:02:53 +02:00
commit a196c3387e
Signed by: muellerr
GPG Key ID: A649FB78196E3849
186 changed files with 3271 additions and 1433 deletions

View File

@ -10,8 +10,11 @@ and this project adheres to [Semantic Versioning](http://semver.org/).
## Fixes ## Fixes
- Important bugfix in CFDP PDU header format: The entity length field and the transaction sequence
number fields stored the actual length of the field instead of the length minus 1 like specified
in the CFDP standard.
- PUS Health Service: Size check for set health command. - PUS Health Service: Size check for set health command.
Perform operation completion for announce health command. Perform operation completion for announce health command.
https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/746 https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/746
- Linux OSAL `getUptime` fix: Check validity of `/proc/uptime` file before reading uptime. - Linux OSAL `getUptime` fix: Check validity of `/proc/uptime` file before reading uptime.
https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/745 https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/745
@ -22,6 +25,7 @@ and this project adheres to [Semantic Versioning](http://semver.org/).
- add CFDP subsystem ID - add CFDP subsystem ID
https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/742 https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/742
- `PusTmZcWriter` now exposes API to set message counter field.
## Changed ## Changed
- Bump ETL version to 20.35.14 - Bump ETL version to 20.35.14
@ -32,6 +36,7 @@ and this project adheres to [Semantic Versioning](http://semver.org/).
https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/743 https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/743
- Assert that `FixedArrayList` is larger than 0 at compile time. - Assert that `FixedArrayList` is larger than 0 at compile time.
https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/740 https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/740
- Health functions are virtual now.
# [v6.0.0] 2023-02-10 # [v6.0.0] 2023-02-10
@ -107,6 +112,8 @@ and this project adheres to [Semantic Versioning](http://semver.org/).
## Added ## Added
- `CServiceHealthCommanding`: Add announce all health info implementation
PR: https://egit.irs.uni-stuttgart.de/eive/fsfw/pulls/122
- Empty constructor for `CdsShortTimeStamper` which does not do an object manager registration. - Empty constructor for `CdsShortTimeStamper` which does not do an object manager registration.
PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/730 PR: https://egit.irs.uni-stuttgart.de/fsfw/fsfw/pulls/730
- `Service9TimeManagement`: Add `DUMP_TIME` (129) subservice. - `Service9TimeManagement`: Add `DUMP_TIME` (129) subservice.

View File

@ -51,7 +51,10 @@ exclude_patterns = ["_build", "Thumbs.db", ".DS_Store"]
html_theme = "alabaster" html_theme = "alabaster"
html_theme_options = { html_theme_options = {
"extra_nav_links": {"Impressum" : "https://www.uni-stuttgart.de/impressum", "Datenschutz": "https://info.irs.uni-stuttgart.de/datenschutz/datenschutzWebmit.html"} "extra_nav_links": {
"Impressum": "https://www.uni-stuttgart.de/impressum",
"Datenschutz": "https://info.irs.uni-stuttgart.de/datenschutz/datenschutzWebmit.html",
}
} }

View File

@ -59,17 +59,24 @@ void ActionHelper::setQueueToUse(MessageQueueIF* queue) { queueToUse = queue; }
void ActionHelper::prepareExecution(MessageQueueId_t commandedBy, ActionId_t actionId, void ActionHelper::prepareExecution(MessageQueueId_t commandedBy, ActionId_t actionId,
store_address_t dataAddress) { store_address_t dataAddress) {
bool hasAdditionalData = false;
const uint8_t* dataPtr = nullptr; const uint8_t* dataPtr = nullptr;
size_t size = 0; size_t size = 0;
ReturnValue_t result = ipcStore->getData(dataAddress, &dataPtr, &size); ReturnValue_t result;
if (result != returnvalue::OK) { if (dataAddress != store_address_t::invalid()) {
CommandMessage reply; hasAdditionalData = true;
ActionMessage::setStepReply(&reply, actionId, 0, result); ReturnValue_t result = ipcStore->getData(dataAddress, &dataPtr, &size);
queueToUse->sendMessage(commandedBy, &reply); if (result != returnvalue::OK) {
return; CommandMessage reply;
ActionMessage::setStepReply(&reply, actionId, 0, result);
queueToUse->sendMessage(commandedBy, &reply);
return;
}
} }
result = owner->executeAction(actionId, commandedBy, dataPtr, size); result = owner->executeAction(actionId, commandedBy, dataPtr, size);
ipcStore->deleteData(dataAddress); if (hasAdditionalData) {
ipcStore->deleteData(dataAddress);
}
if (result == HasActionsIF::EXECUTION_FINISHED) { if (result == HasActionsIF::EXECUTION_FINISHED) {
CommandMessage reply; CommandMessage reply;
ActionMessage::setCompletionReply(&reply, actionId, true, result); ActionMessage::setCompletionReply(&reply, actionId, true, result);

View File

@ -16,8 +16,8 @@ class CommandActionHelper {
public: public:
explicit CommandActionHelper(CommandsActionsIF* owner); explicit CommandActionHelper(CommandsActionsIF* owner);
virtual ~CommandActionHelper(); virtual ~CommandActionHelper();
ReturnValue_t commandAction(object_id_t commandTo, ActionId_t actionId, const uint8_t* data, ReturnValue_t commandAction(object_id_t commandTo, ActionId_t actionId,
uint32_t size); const uint8_t* data = nullptr, uint32_t size = 0);
ReturnValue_t commandAction(object_id_t commandTo, ActionId_t actionId, SerializeIF* data); ReturnValue_t commandAction(object_id_t commandTo, ActionId_t actionId, SerializeIF* data);
ReturnValue_t initialize(); ReturnValue_t initialize();
ReturnValue_t handleReply(CommandMessage* reply); ReturnValue_t handleReply(CommandMessage* reply);

View File

@ -2,7 +2,9 @@
#define FSFW_CFDP_H #define FSFW_CFDP_H
#include "cfdp/definitions.h" #include "cfdp/definitions.h"
#include "cfdp/handler/DestHandler.h"
#include "cfdp/handler/FaultHandlerBase.h" #include "cfdp/handler/FaultHandlerBase.h"
#include "cfdp/helpers.h"
#include "cfdp/tlv/Lv.h" #include "cfdp/tlv/Lv.h"
#include "cfdp/tlv/StringLv.h" #include "cfdp/tlv/StringLv.h"
#include "cfdp/tlv/Tlv.h" #include "cfdp/tlv/Tlv.h"

View File

@ -1 +1,2 @@
target_sources(${LIB_FSFW_NAME} PRIVATE FaultHandlerBase.cpp UserBase.cpp) target_sources(${LIB_FSFW_NAME} PRIVATE SourceHandler.cpp DestHandler.cpp
FaultHandlerBase.cpp UserBase.cpp)

View File

@ -0,0 +1,546 @@
#include "DestHandler.h"
#include <etl/crc32.h>
#include <utility>
#include "fsfw/FSFW.h"
#include "fsfw/cfdp/pdu/EofPduReader.h"
#include "fsfw/cfdp/pdu/FileDataReader.h"
#include "fsfw/cfdp/pdu/FinishedPduCreator.h"
#include "fsfw/cfdp/pdu/PduHeaderReader.h"
#include "fsfw/objectmanager.h"
#include "fsfw/tmtcservices/TmTcMessage.h"
using namespace returnvalue;
cfdp::DestHandler::DestHandler(DestHandlerParams params, FsfwParams fsfwParams)
: tlvVec(params.maxTlvsInOnePdu),
userTlvVec(params.maxTlvsInOnePdu),
dp(std::move(params)),
fp(fsfwParams),
tp(params.maxFilenameLen) {
tp.pduConf.direction = cfdp::Direction::TOWARDS_SENDER;
}
const cfdp::DestHandler::FsmResult& cfdp::DestHandler::performStateMachine() {
ReturnValue_t result;
uint8_t errorIdx = 0;
fsmRes.resetOfIteration();
if (fsmRes.step == TransactionStep::IDLE) {
for (auto infoIter = dp.packetListRef.begin(); infoIter != dp.packetListRef.end();) {
if (infoIter->pduType == PduType::FILE_DIRECTIVE and
infoIter->directiveType == FileDirective::METADATA) {
result = handleMetadataPdu(*infoIter);
checkAndHandleError(result, errorIdx);
// Store data was deleted in PDU handler because a store guard is used
dp.packetListRef.erase(infoIter++);
} else {
infoIter++;
}
}
if (fsmRes.step == TransactionStep::IDLE) {
// To decrease the already high complexity of the software, all packets arriving before
// a metadata PDU are deleted.
for (auto infoIter = dp.packetListRef.begin(); infoIter != dp.packetListRef.end();) {
fp.tcStore->deleteData(infoIter->storeId);
infoIter++;
}
dp.packetListRef.clear();
}
if (fsmRes.step != TransactionStep::IDLE) {
fsmRes.callStatus = CallStatus::CALL_AGAIN;
}
return updateFsmRes(errorIdx);
}
if (fsmRes.state == CfdpStates::BUSY_CLASS_1_NACKED) {
if (fsmRes.step == TransactionStep::RECEIVING_FILE_DATA_PDUS) {
for (auto infoIter = dp.packetListRef.begin(); infoIter != dp.packetListRef.end();) {
if (infoIter->pduType == PduType::FILE_DATA) {
result = handleFileDataPdu(*infoIter);
checkAndHandleError(result, errorIdx);
// Store data was deleted in PDU handler because a store guard is used
dp.packetListRef.erase(infoIter++);
} else if (infoIter->pduType == PduType::FILE_DIRECTIVE and
infoIter->directiveType == FileDirective::EOF_DIRECTIVE) {
// TODO: Support for check timer missing
result = handleEofPdu(*infoIter);
checkAndHandleError(result, errorIdx);
// Store data was deleted in PDU handler because a store guard is used
dp.packetListRef.erase(infoIter++);
} else {
infoIter++;
}
}
}
if (fsmRes.step == TransactionStep::TRANSFER_COMPLETION) {
result = handleTransferCompletion();
checkAndHandleError(result, errorIdx);
}
if (fsmRes.step == TransactionStep::SENDING_FINISHED_PDU) {
result = sendFinishedPdu();
checkAndHandleError(result, errorIdx);
finish();
}
return updateFsmRes(errorIdx);
}
if (fsmRes.state == CfdpStates::BUSY_CLASS_2_ACKED) {
// TODO: Will be implemented at a later stage
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "CFDP state machine for acknowledged mode not implemented yet" << std::endl;
#endif
}
return updateFsmRes(errorIdx);
}
ReturnValue_t cfdp::DestHandler::passPacket(PacketInfo packet) {
if (dp.packetListRef.full()) {
return FAILED;
}
dp.packetListRef.push_back(packet);
return OK;
}
ReturnValue_t cfdp::DestHandler::initialize() {
if (fp.tmStore == nullptr) {
fp.tmStore = ObjectManager::instance()->get<StorageManagerIF>(objects::TM_STORE);
if (fp.tmStore == nullptr) {
return FAILED;
}
}
if (fp.tcStore == nullptr) {
fp.tcStore = ObjectManager::instance()->get<StorageManagerIF>(objects::TC_STORE);
if (fp.tcStore == nullptr) {
return FAILED;
}
}
if (fp.msgQueue == nullptr) {
return FAILED;
}
return OK;
}
ReturnValue_t cfdp::DestHandler::handleMetadataPdu(const PacketInfo& info) {
// Process metadata PDU
auto constAccessorPair = fp.tcStore->getData(info.storeId);
if (constAccessorPair.first != OK) {
// TODO: This is not a CFDP error. Event and/or warning?
return constAccessorPair.first;
}
cfdp::StringLv sourceFileName;
cfdp::StringLv destFileName;
MetadataInfo metadataInfo(tp.fileSize, sourceFileName, destFileName);
cfdp::Tlv* tlvArrayAsPtr = tlvVec.data();
metadataInfo.setOptionsArray(&tlvArrayAsPtr, std::nullopt, tlvVec.size());
MetadataPduReader reader(constAccessorPair.second.data(), constAccessorPair.second.size(),
metadataInfo);
ReturnValue_t result = reader.parseData();
// TODO: The standard does not really specify what happens if this kind of error happens
// I think it might be a good idea to cache some sort of error code, which
// is translated into a warning and/or event by an upper layer
if (result != OK) {
return handleMetadataParseError(result, constAccessorPair.second.data(),
constAccessorPair.second.size());
}
return startTransaction(reader, metadataInfo);
}
ReturnValue_t cfdp::DestHandler::handleFileDataPdu(const cfdp::PacketInfo& info) {
// Process file data PDU
auto constAccessorPair = fp.tcStore->getData(info.storeId);
if (constAccessorPair.first != OK) {
// TODO: This is not a CFDP error. Event and/or warning?
return constAccessorPair.first;
}
cfdp::FileSize offset;
FileDataInfo fdInfo(offset);
FileDataReader reader(constAccessorPair.second.data(), constAccessorPair.second.size(), fdInfo);
ReturnValue_t result = reader.parseData();
if (result != OK) {
return result;
}
size_t fileSegmentLen = 0;
const uint8_t* fileData = fdInfo.getFileData(&fileSegmentLen);
FileOpParams fileOpParams(tp.destName.data(), fileSegmentLen);
fileOpParams.offset = offset.value();
if (dp.cfg.indicCfg.fileSegmentRecvIndicRequired) {
FileSegmentRecvdParams segParams;
segParams.offset = offset.value();
segParams.id = tp.transactionId;
segParams.length = fileSegmentLen;
segParams.recContState = fdInfo.getRecordContinuationState();
size_t segmentMetadatLen = 0;
auto* segMetadata = fdInfo.getSegmentMetadata(&segmentMetadatLen);
segParams.segmentMetadata = {segMetadata, segmentMetadatLen};
dp.user.fileSegmentRecvdIndication(segParams);
}
result = dp.user.vfs.writeToFile(fileOpParams, fileData);
if (result != returnvalue::OK) {
// TODO: Proper Error handling
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::error << "cfdp::DestHandler: VFS file write error with code 0x" << std::hex << std::setw(2)
<< result << std::endl;
#endif
tp.vfsErrorCount++;
if (tp.vfsErrorCount < 3) {
// TODO: Provide execution step as parameter
fp.eventReporter->forwardEvent(events::FILESTORE_ERROR, static_cast<uint8_t>(fsmRes.step),
result);
}
return result;
} else {
tp.deliveryStatus = FileDeliveryStatus::RETAINED_IN_FILESTORE;
tp.vfsErrorCount = 0;
}
if (offset.value() + fileSegmentLen > tp.progress) {
tp.progress = offset.value() + fileSegmentLen;
}
return result;
}
ReturnValue_t cfdp::DestHandler::handleEofPdu(const cfdp::PacketInfo& info) {
// Process EOF PDU
auto constAccessorPair = fp.tcStore->getData(info.storeId);
if (constAccessorPair.first != OK) {
// TODO: This is not a CFDP error. Event and/or warning?
return constAccessorPair.first;
}
EofInfo eofInfo(nullptr);
EofPduReader reader(constAccessorPair.second.data(), constAccessorPair.second.size(), eofInfo);
ReturnValue_t result = reader.parseData();
if (result != OK) {
return result;
}
// TODO: Error handling
if (eofInfo.getConditionCode() == ConditionCode::NO_ERROR) {
tp.crc = eofInfo.getChecksum();
uint64_t fileSizeFromEof = eofInfo.getFileSize().value();
// CFDP 4.6.1.2.9: Declare file size error if progress exceeds file size
if (fileSizeFromEof > tp.progress) {
// TODO: File size error
}
tp.fileSize.setFileSize(fileSizeFromEof, std::nullopt);
}
if (dp.cfg.indicCfg.eofRecvIndicRequired) {
dp.user.eofRecvIndication(getTransactionId());
}
if (fsmRes.step == TransactionStep::RECEIVING_FILE_DATA_PDUS) {
if (fsmRes.state == CfdpStates::BUSY_CLASS_1_NACKED) {
fsmRes.step = TransactionStep::TRANSFER_COMPLETION;
} else if (fsmRes.state == CfdpStates::BUSY_CLASS_2_ACKED) {
fsmRes.step = TransactionStep::SENDING_ACK_PDU;
}
}
return returnvalue::OK;
}
ReturnValue_t cfdp::DestHandler::handleMetadataParseError(ReturnValue_t result,
const uint8_t* rawData, size_t maxSize) {
// TODO: try to extract destination ID for error
// TODO: Invalid metadata PDU.
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "Parsing Metadata PDU failed with code " << result << std::endl;
#else
#endif
PduHeaderReader headerReader(rawData, maxSize);
result = headerReader.parseData();
if (result != OK) {
// TODO: Now this really should not happen. Warning or error,
// yield or cache appropriate returnvalue
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "Parsing Header failed" << std::endl;
#else
#endif
// TODO: Trigger appropriate event
return result;
}
cfdp::EntityId destId;
headerReader.getDestId(destId);
RemoteEntityCfg* remoteCfg;
if (not dp.remoteCfgTable.getRemoteCfg(destId, &remoteCfg)) {
// TODO: No remote config for dest ID. I consider this a configuration error, which is not
// covered by the standard.
// Warning or error, yield or cache appropriate returnvalue
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "No remote config exists for destination ID" << std::endl;
#else
#endif
// TODO: Trigger appropriate event
}
// TODO: Appropriate returnvalue?
return returnvalue::FAILED;
}
ReturnValue_t cfdp::DestHandler::startTransaction(MetadataPduReader& reader, MetadataInfo& info) {
if (fsmRes.state != CfdpStates::IDLE) {
// According to standard, discard metadata PDU if we are busy
return OK;
}
ReturnValue_t result = OK;
size_t sourceNameSize = 0;
const uint8_t* sourceNamePtr = info.getSourceFileName().getValue(&sourceNameSize);
if (sourceNameSize + 1 > tp.sourceName.size()) {
fileErrorHandler(events::FILENAME_TOO_LARGE_ERROR, 0, "source filename too large");
return FAILED;
}
std::memcpy(tp.sourceName.data(), sourceNamePtr, sourceNameSize);
tp.sourceName[sourceNameSize] = '\0';
size_t destNameSize = 0;
const uint8_t* destNamePtr = info.getDestFileName().getValue(&destNameSize);
if (destNameSize + 1 > tp.destName.size()) {
fileErrorHandler(events::FILENAME_TOO_LARGE_ERROR, 0, "dest filename too large");
return FAILED;
}
std::memcpy(tp.destName.data(), destNamePtr, destNameSize);
tp.destName[destNameSize] = '\0';
// If both dest name size and source name size are 0, we are dealing with a metadata only PDU,
// so there is no need to create a file or truncate an existing file
if (destNameSize > 0 and sourceNameSize > 0) {
FilesystemParams fparams(tp.destName.data());
// handling to allow only specifying target directory. Example:
// Source path /test/hello.txt, dest path /tmp -> dest path /tmp/hello.txt
if (dp.user.vfs.isDirectory(tp.destName.data())) {
result = tryBuildingAbsoluteDestName(destNameSize);
if (result != OK) {
return result;
}
}
if (dp.user.vfs.fileExists(fparams)) {
result = dp.user.vfs.truncateFile(fparams);
if (result != returnvalue::OK) {
fileErrorHandler(events::FILESTORE_ERROR, result, "file truncation error");
return FAILED;
// TODO: Relevant for filestore rejection error?
}
} else {
result = dp.user.vfs.createFile(fparams);
if (result != OK) {
fileErrorHandler(events::FILESTORE_ERROR, result, "file creation error");
return FAILED;
// TODO: Relevant for filestore rejection error?
}
}
}
EntityId sourceId;
reader.getSourceId(sourceId);
if (not dp.remoteCfgTable.getRemoteCfg(sourceId, &tp.remoteCfg)) {
// TODO: Warning, event etc.
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "cfdp::DestHandler" << __func__
<< ": No remote configuration found for destination ID "
<< tp.pduConf.sourceId.getValue() << std::endl;
#endif
return FAILED;
}
fsmRes.step = TransactionStep::TRANSACTION_START;
if (reader.getTransmissionMode() == TransmissionMode::UNACKNOWLEDGED) {
fsmRes.state = CfdpStates::BUSY_CLASS_1_NACKED;
} else if (reader.getTransmissionMode() == TransmissionMode::ACKNOWLEDGED) {
fsmRes.state = CfdpStates::BUSY_CLASS_2_ACKED;
}
tp.checksumType = info.getChecksumType();
tp.closureRequested = info.isClosureRequested();
reader.fillConfig(tp.pduConf);
tp.pduConf.direction = Direction::TOWARDS_SENDER;
tp.transactionId.entityId = tp.pduConf.sourceId;
tp.transactionId.seqNum = tp.pduConf.seqNum;
fsmRes.step = TransactionStep::RECEIVING_FILE_DATA_PDUS;
MetadataRecvdParams params(tp.transactionId, tp.pduConf.sourceId);
params.fileSize = tp.fileSize.getSize();
params.destFileName = tp.destName.data();
params.sourceFileName = tp.sourceName.data();
params.msgsToUserArray = dynamic_cast<MessageToUserTlv*>(userTlvVec.data());
params.msgsToUserLen = info.getOptionsLen();
dp.user.metadataRecvdIndication(params);
return result;
}
cfdp::CfdpStates cfdp::DestHandler::getCfdpState() const { return fsmRes.state; }
ReturnValue_t cfdp::DestHandler::handleTransferCompletion() {
ReturnValue_t result;
if (tp.checksumType != ChecksumType::NULL_CHECKSUM) {
result = checksumVerification();
if (result != OK) {
// TODO: Warning / error handling?
}
} else {
tp.conditionCode = ConditionCode::NO_ERROR;
}
result = noticeOfCompletion();
if (result != OK) {
}
if (fsmRes.state == CfdpStates::BUSY_CLASS_1_NACKED) {
if (tp.closureRequested) {
fsmRes.step = TransactionStep::SENDING_FINISHED_PDU;
} else {
finish();
}
} else if (fsmRes.state == CfdpStates::BUSY_CLASS_2_ACKED) {
fsmRes.step = TransactionStep::SENDING_FINISHED_PDU;
}
return OK;
}
ReturnValue_t cfdp::DestHandler::tryBuildingAbsoluteDestName(size_t destNameSize) {
char baseNameBuf[tp.destName.size()]{};
FilesystemParams fparamsSrc(tp.sourceName.data());
size_t baseNameLen = 0;
ReturnValue_t result =
dp.user.vfs.getBaseFilename(fparamsSrc, baseNameBuf, sizeof(baseNameBuf), baseNameLen);
if (result != returnvalue::OK or baseNameLen == 0) {
fileErrorHandler(events::FILENAME_TOO_LARGE_ERROR, 0, "error retrieving source base name");
return FAILED;
}
// Destination name + slash + base name + null termination
if (destNameSize + 1 + baseNameLen + 1 > tp.destName.size()) {
fileErrorHandler(events::FILENAME_TOO_LARGE_ERROR, 0,
"dest filename too large after adding source base name");
return FAILED;
}
tp.destName[destNameSize++] = '/';
std::memcpy(tp.destName.data() + destNameSize, baseNameBuf, baseNameLen);
destNameSize += baseNameLen;
tp.destName[destNameSize++] = '\0';
return OK;
}
void cfdp::DestHandler::fileErrorHandler(Event event, ReturnValue_t result, const char* info) {
fp.eventReporter->forwardEvent(events::FILENAME_TOO_LARGE_ERROR,
static_cast<uint8_t>(fsmRes.step), result);
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "cfdp::DestHandler: " << info << std::endl;
#endif
}
void cfdp::DestHandler::finish() {
tp.reset();
dp.packetListRef.clear();
fsmRes.state = CfdpStates::IDLE;
fsmRes.step = TransactionStep::IDLE;
}
ReturnValue_t cfdp::DestHandler::checksumVerification() {
std::array<uint8_t, 1024> buf{};
// TODO: Checksum verification and notice of completion
etl::crc32 crcCalc;
uint64_t currentOffset = 0;
FileOpParams params(tp.destName.data(), tp.fileSize.value());
while (currentOffset < tp.fileSize.value()) {
uint64_t readLen;
if (currentOffset + buf.size() > tp.fileSize.value()) {
readLen = tp.fileSize.value() - currentOffset;
} else {
readLen = buf.size();
}
if (readLen > 0) {
params.offset = currentOffset;
params.size = readLen;
auto result = dp.user.vfs.readFromFile(params, buf.data(), buf.size());
if (result != OK) {
// TODO: I think this is a case for a filestore rejection, but it might sense to print
// a warning or trigger an event because this should generally not happen
return FAILED;
}
crcCalc.add(buf.begin(), buf.begin() + readLen);
}
currentOffset += readLen;
}
uint32_t value = crcCalc.value();
if (value == tp.crc) {
tp.conditionCode = ConditionCode::NO_ERROR;
tp.deliveryCode = FileDeliveryCode::DATA_COMPLETE;
} else {
// TODO: Proper error handling
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "CRC check for file " << tp.destName.data() << " failed" << std::endl;
#endif
tp.conditionCode = ConditionCode::FILE_CHECKSUM_FAILURE;
}
return OK;
}
ReturnValue_t cfdp::DestHandler::noticeOfCompletion() {
if (dp.cfg.indicCfg.transactionFinishedIndicRequired) {
TransactionFinishedParams params(tp.transactionId, tp.conditionCode, tp.deliveryCode,
tp.deliveryStatus);
dp.user.transactionFinishedIndication(params);
}
return OK;
}
ReturnValue_t cfdp::DestHandler::sendFinishedPdu() {
FinishedInfo info(tp.conditionCode, tp.deliveryCode, tp.deliveryStatus);
FinishPduCreator finishedPdu(tp.pduConf, info);
store_address_t storeId;
uint8_t* dataPtr = nullptr;
ReturnValue_t result =
fp.tmStore->getFreeElement(&storeId, finishedPdu.getSerializedSize(), &dataPtr);
if (result != OK) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "cfdp::DestHandler:sendFinishedPdu: Getting store slot failed" << std::endl;
#endif
fp.eventReporter->forwardEvent(events::STORE_ERROR, result, 0);
return result;
}
size_t serLen = 0;
result = finishedPdu.serialize(dataPtr, serLen, finishedPdu.getSerializedSize());
if (result != OK) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "cfdp::DestHandler::sendFinishedPdu: Serializing Finished PDU failed"
<< std::endl;
#endif
fp.eventReporter->forwardEvent(events::SERIALIZATION_ERROR, result, 0);
return result;
}
TmTcMessage msg(storeId);
result = fp.msgQueue->sendMessage(fp.packetDest.getReportReceptionQueue(), &msg);
if (result != OK) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "cfdp::DestHandler::sendFinishedPdu: Sending PDU failed" << std::endl;
#endif
fp.eventReporter->forwardEvent(events::MSG_QUEUE_ERROR, result, 0);
return result;
}
fsmRes.packetsSent++;
return OK;
}
cfdp::DestHandler::TransactionStep cfdp::DestHandler::getTransactionStep() const {
return fsmRes.step;
}
const cfdp::DestHandler::FsmResult& cfdp::DestHandler::updateFsmRes(uint8_t errors) {
fsmRes.errors = errors;
fsmRes.result = OK;
if (fsmRes.errors > 0) {
fsmRes.result = FAILED;
}
return fsmRes;
}
const cfdp::TransactionId& cfdp::DestHandler::getTransactionId() const { return tp.transactionId; }
void cfdp::DestHandler::checkAndHandleError(ReturnValue_t result, uint8_t& errorIdx) {
if (result != OK and errorIdx < 3) {
fsmRes.errorCodes[errorIdx] = result;
errorIdx++;
}
}
void cfdp::DestHandler::setMsgQueue(MessageQueueIF& queue) { fp.msgQueue = &queue; }
void cfdp::DestHandler::setEventReporter(EventReportingProxyIF& reporter) {
fp.eventReporter = &reporter;
}
const cfdp::DestHandlerParams& cfdp::DestHandler::getDestHandlerParams() const { return dp; }
StorageManagerIF* cfdp::DestHandler::getTmStore() const { return fp.tmStore; }
StorageManagerIF* cfdp::DestHandler::getTcStore() const { return fp.tcStore; }

View File

@ -0,0 +1,206 @@
#ifndef FSFW_CFDP_CFDPDESTHANDLER_H
#define FSFW_CFDP_CFDPDESTHANDLER_H
#include <etl/list.h>
#include <etl/set.h>
#include <optional>
#include <utility>
#include "RemoteConfigTableIF.h"
#include "UserBase.h"
#include "defs.h"
#include "fsfw/cfdp/handler/mib.h"
#include "fsfw/cfdp/pdu/MetadataPduReader.h"
#include "fsfw/cfdp/pdu/PduConfig.h"
#include "fsfw/container/DynamicFIFO.h"
#include "fsfw/storagemanager/StorageManagerIF.h"
#include "fsfw/storagemanager/storeAddress.h"
#include "fsfw/tmtcservices/AcceptsTelemetryIF.h"
namespace cfdp {
struct PacketInfo {
PacketInfo(PduType type, store_address_t storeId,
std::optional<FileDirective> directive = std::nullopt)
: pduType(type), directiveType(directive), storeId(storeId) {}
PduType pduType = PduType::FILE_DATA;
std::optional<FileDirective> directiveType = FileDirective::INVALID_DIRECTIVE;
store_address_t storeId = store_address_t::invalid();
PacketInfo() = default;
};
template <size_t SIZE>
using LostSegmentsList = etl::set<etl::pair<uint64_t, uint64_t>, SIZE>;
template <size_t SIZE>
using PacketInfoList = etl::list<PacketInfo, SIZE>;
using LostSegmentsListBase = etl::iset<etl::pair<uint64_t, uint64_t>>;
using PacketInfoListBase = etl::ilist<PacketInfo>;
struct DestHandlerParams {
DestHandlerParams(LocalEntityCfg cfg, UserBase& user, RemoteConfigTableIF& remoteCfgTable,
PacketInfoListBase& packetList,
// TODO: This container can potentially take tons of space. For a better
// memory efficient implementation, an additional abstraction could be
// be used so users can use uint32_t as the pair type
LostSegmentsListBase& lostSegmentsContainer)
: cfg(std::move(cfg)),
user(user),
remoteCfgTable(remoteCfgTable),
packetListRef(packetList),
lostSegmentsContainer(lostSegmentsContainer) {}
LocalEntityCfg cfg;
UserBase& user;
RemoteConfigTableIF& remoteCfgTable;
PacketInfoListBase& packetListRef;
LostSegmentsListBase& lostSegmentsContainer;
uint8_t maxTlvsInOnePdu = 10;
size_t maxFilenameLen = 255;
};
struct FsfwParams {
FsfwParams(AcceptsTelemetryIF& packetDest, MessageQueueIF* msgQueue,
EventReportingProxyIF* eventReporter, StorageManagerIF& tcStore,
StorageManagerIF& tmStore)
: FsfwParams(packetDest, msgQueue, eventReporter) {
this->tcStore = &tcStore;
this->tmStore = &tmStore;
}
FsfwParams(AcceptsTelemetryIF& packetDest, MessageQueueIF* msgQueue,
EventReportingProxyIF* eventReporter)
: packetDest(packetDest), msgQueue(msgQueue), eventReporter(eventReporter) {}
AcceptsTelemetryIF& packetDest;
MessageQueueIF* msgQueue;
EventReportingProxyIF* eventReporter = nullptr;
StorageManagerIF* tcStore = nullptr;
StorageManagerIF* tmStore = nullptr;
};
enum class CallStatus { DONE, CALL_AFTER_DELAY, CALL_AGAIN };
class DestHandler {
public:
enum class TransactionStep : uint8_t {
IDLE = 0,
TRANSACTION_START = 1,
RECEIVING_FILE_DATA_PDUS = 2,
SENDING_ACK_PDU = 3,
TRANSFER_COMPLETION = 4,
SENDING_FINISHED_PDU = 5
};
struct FsmResult {
public:
ReturnValue_t result = returnvalue::OK;
CallStatus callStatus = CallStatus::CALL_AFTER_DELAY;
TransactionStep step = TransactionStep::IDLE;
CfdpStates state = CfdpStates::IDLE;
uint32_t packetsSent = 0;
uint8_t errors = 0;
std::array<ReturnValue_t, 3> errorCodes = {};
void resetOfIteration() {
result = returnvalue::OK;
callStatus = CallStatus::CALL_AFTER_DELAY;
packetsSent = 0;
errors = 0;
errorCodes.fill(returnvalue::OK);
}
};
/**
* Will be returned if it is advisable to call the state machine operation call again
*/
ReturnValue_t PARTIAL_SUCCESS = returnvalue::makeCode(0, 2);
ReturnValue_t FAILURE = returnvalue::makeCode(0, 3);
explicit DestHandler(DestHandlerParams handlerParams, FsfwParams fsfwParams);
/**
*
* @return
* - @c returnvalue::OK State machine OK for this execution cycle
* - @c CALL_FSM_AGAIN State machine should be called again.
*/
const FsmResult& performStateMachine();
void setMsgQueue(MessageQueueIF& queue);
void setEventReporter(EventReportingProxyIF& reporter);
ReturnValue_t passPacket(PacketInfo packet);
ReturnValue_t initialize();
[[nodiscard]] CfdpStates getCfdpState() const;
[[nodiscard]] TransactionStep getTransactionStep() const;
[[nodiscard]] const TransactionId& getTransactionId() const;
[[nodiscard]] const DestHandlerParams& getDestHandlerParams() const;
[[nodiscard]] StorageManagerIF* getTcStore() const;
[[nodiscard]] StorageManagerIF* getTmStore() const;
private:
struct TransactionParams {
// Initialize char vectors with length + 1 for 0 termination
explicit TransactionParams(size_t maxFileNameLen)
: sourceName(maxFileNameLen + 1), destName(maxFileNameLen + 1) {}
void reset() {
pduConf = PduConfig();
transactionId = TransactionId();
std::fill(sourceName.begin(), sourceName.end(), '\0');
std::fill(destName.begin(), destName.end(), '\0');
fileSize.setFileSize(0, false);
conditionCode = ConditionCode::NO_ERROR;
deliveryCode = FileDeliveryCode::DATA_INCOMPLETE;
deliveryStatus = FileDeliveryStatus::DISCARDED_DELIBERATELY;
crc = 0;
progress = 0;
remoteCfg = nullptr;
closureRequested = false;
vfsErrorCount = 0;
checksumType = ChecksumType::NULL_CHECKSUM;
}
ChecksumType checksumType = ChecksumType::NULL_CHECKSUM;
bool closureRequested = false;
uint16_t vfsErrorCount = 0;
std::vector<char> sourceName;
std::vector<char> destName;
cfdp::FileSize fileSize;
TransactionId transactionId;
PduConfig pduConf;
ConditionCode conditionCode = ConditionCode::NO_ERROR;
FileDeliveryCode deliveryCode = FileDeliveryCode::DATA_INCOMPLETE;
FileDeliveryStatus deliveryStatus = FileDeliveryStatus::DISCARDED_DELIBERATELY;
uint32_t crc = 0;
uint64_t progress = 0;
RemoteEntityCfg* remoteCfg = nullptr;
};
std::vector<cfdp::Tlv> tlvVec;
std::vector<cfdp::Tlv> userTlvVec;
DestHandlerParams dp;
FsfwParams fp;
TransactionParams tp;
FsmResult fsmRes;
ReturnValue_t startTransaction(MetadataPduReader& reader, MetadataInfo& info);
ReturnValue_t handleMetadataPdu(const PacketInfo& info);
ReturnValue_t handleFileDataPdu(const PacketInfo& info);
ReturnValue_t handleEofPdu(const PacketInfo& info);
ReturnValue_t handleMetadataParseError(ReturnValue_t result, const uint8_t* rawData,
size_t maxSize);
ReturnValue_t handleTransferCompletion();
ReturnValue_t tryBuildingAbsoluteDestName(size_t destNameSize);
ReturnValue_t sendFinishedPdu();
ReturnValue_t noticeOfCompletion();
ReturnValue_t checksumVerification();
void fileErrorHandler(Event event, ReturnValue_t result, const char* info);
const FsmResult& updateFsmRes(uint8_t errors);
void checkAndHandleError(ReturnValue_t result, uint8_t& errorIdx);
void finish();
};
} // namespace cfdp
#endif // FSFW_CFDP_CFDPDESTHANDLER_H

View File

@ -0,0 +1 @@
#include "SourceHandler.h"

View File

@ -0,0 +1,6 @@
#ifndef FSFW_CFDP_CFDPSOURCEHANDLER_H
#define FSFW_CFDP_CFDPSOURCEHANDLER_H
class SourceHandler {};
#endif // FSFW_CFDP_CFDPSOURCEHANDLER_H

View File

@ -5,5 +5,18 @@ namespace cfdp {
enum class CfdpStates { IDLE, BUSY_CLASS_1_NACKED, BUSY_CLASS_2_ACKED, SUSPENDED }; enum class CfdpStates { IDLE, BUSY_CLASS_1_NACKED, BUSY_CLASS_2_ACKED, SUSPENDED };
} static constexpr uint8_t SSID = SUBSYSTEM_ID::CFDP;
namespace events {
static constexpr Event STORE_ERROR = event::makeEvent(SSID, 0, severity::LOW);
static constexpr Event MSG_QUEUE_ERROR = event::makeEvent(SSID, 1, severity::LOW);
static constexpr Event SERIALIZATION_ERROR = event::makeEvent(SSID, 2, severity::LOW);
static constexpr Event FILESTORE_ERROR = event::makeEvent(SSID, 3, severity::LOW);
//! [EXPORT] : [COMMENT] P1: Transaction step ID, P2: 0 for source file name, 1 for dest file name
static constexpr Event FILENAME_TOO_LARGE_ERROR = event::makeEvent(SSID, 4, severity::LOW);
} // namespace events
} // namespace cfdp
#endif // FSFW_CFDP_HANDLER_DEFS_H #endif // FSFW_CFDP_HANDLER_DEFS_H

View File

@ -24,8 +24,8 @@ ReturnValue_t HeaderCreator::serialize(uint8_t **buffer, size_t *size, size_t ma
*buffer += 1; *buffer += 1;
**buffer = pduDataFieldLen & 0x00ff; **buffer = pduDataFieldLen & 0x00ff;
*buffer += 1; *buffer += 1;
**buffer = segmentationCtrl << 7 | pduConf.sourceId.getWidth() << 4 | segmentMetadataFlag << 3 | **buffer = segmentationCtrl << 7 | ((pduConf.sourceId.getWidth() - 1) << 4) |
pduConf.seqNum.getWidth(); segmentMetadataFlag << 3 | (pduConf.seqNum.getWidth() - 1);
*buffer += 1; *buffer += 1;
*size += 4; *size += 4;
ReturnValue_t result = pduConf.sourceId.serialize(buffer, size, maxSize, streamEndianness); ReturnValue_t result = pduConf.sourceId.serialize(buffer, size, maxSize, streamEndianness);

View File

@ -78,11 +78,11 @@ cfdp::SegmentationControl PduHeaderReader::getSegmentationControl() const {
} }
cfdp::WidthInBytes PduHeaderReader::getLenEntityIds() const { cfdp::WidthInBytes PduHeaderReader::getLenEntityIds() const {
return static_cast<cfdp::WidthInBytes>((pointers.fixedHeader->fourthByte >> 4) & 0x07); return static_cast<cfdp::WidthInBytes>(((pointers.fixedHeader->fourthByte >> 4) & 0b111) + 1);
} }
cfdp::WidthInBytes PduHeaderReader::getLenSeqNum() const { cfdp::WidthInBytes PduHeaderReader::getLenSeqNum() const {
return static_cast<cfdp::WidthInBytes>(pointers.fixedHeader->fourthByte & 0x07); return static_cast<cfdp::WidthInBytes>((pointers.fixedHeader->fourthByte & 0b111) + 1);
} }
cfdp::SegmentMetadataFlag PduHeaderReader::getSegmentMetadataFlag() const { cfdp::SegmentMetadataFlag PduHeaderReader::getSegmentMetadataFlag() const {

View File

@ -4,48 +4,31 @@
#include "fsfw/ipc/QueueFactory.h" #include "fsfw/ipc/QueueFactory.h"
#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/objectmanager/ObjectManager.h"
#include "fsfw/subsystem/SubsystemBase.h" #include "fsfw/subsystem/SubsystemBase.h"
#include "fsfw/subsystem/helper.h"
ControllerBase::ControllerBase(object_id_t setObjectId, object_id_t parentId, ControllerBase::ControllerBase(object_id_t setObjectId, size_t commandQueueDepth)
size_t commandQueueDepth)
: SystemObject(setObjectId), : SystemObject(setObjectId),
parentId(parentId),
mode(MODE_OFF), mode(MODE_OFF),
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); }
ReturnValue_t ControllerBase::initialize() { ReturnValue_t ControllerBase::initialize() {
ReturnValue_t result = SystemObject::initialize(); ReturnValue_t result = modeHelper.initialize();
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
return result; return result;
} }
result = healthHelper.initialize();
MessageQueueId_t parentQueue = 0;
if (parentId != objects::NO_OBJECT) {
auto* parent = ObjectManager::instance()->get<SubsystemBase>(parentId);
if (parent == nullptr) {
return returnvalue::FAILED;
}
parentQueue = parent->getCommandQueue();
parent->registerChild(getObjectId());
}
result = healthHelper.initialize(parentQueue);
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
return result; return result;
} }
return SystemObject::initialize();
result = modeHelper.initialize(parentQueue);
if (result != returnvalue::OK) {
return result;
}
return returnvalue::OK;
} }
MessageQueueId_t ControllerBase::getCommandQueue() const { return commandQueue->getId(); } MessageQueueId_t ControllerBase::getCommandQueue() const { return commandQueue->getId(); }
@ -75,7 +58,7 @@ void ControllerBase::handleQueue() {
void ControllerBase::startTransition(Mode_t mode_, Submode_t submode_) { void ControllerBase::startTransition(Mode_t mode_, Submode_t submode_) {
changeHK(this->mode, this->submode, false); changeHK(this->mode, this->submode, false);
triggerEvent(CHANGING_MODE, mode, submode); triggerEvent(CHANGING_MODE, mode_, submode_);
mode = mode_; mode = mode_;
submode = submode_; submode = submode_;
modeHelper.modeChanged(mode, submode); modeHelper.modeChanged(mode, submode);
@ -118,3 +101,13 @@ void ControllerBase::setTaskIF(PeriodicTaskIF* task_) { executingTask = task_; }
void ControllerBase::changeHK(Mode_t mode_, Submode_t submode_, bool enable) {} void ControllerBase::changeHK(Mode_t mode_, Submode_t submode_, bool enable) {}
ReturnValue_t ControllerBase::initializeAfterTaskCreation() { return returnvalue::OK; } ReturnValue_t ControllerBase::initializeAfterTaskCreation() { return returnvalue::OK; }
const HasHealthIF* ControllerBase::getOptHealthIF() const { return this; }
const HasModesIF& ControllerBase::getModeIF() const { return *this; }
ModeTreeChildIF& ControllerBase::getModeTreeChildIF() { return *this; }
ReturnValue_t ControllerBase::connectModeTreeParent(HasModeTreeChildrenIF& parent) {
return modetree::connectModeTreeParent(parent, *this, &healthHelper, modeHelper);
}

View File

@ -6,6 +6,9 @@
#include "fsfw/modes/HasModesIF.h" #include "fsfw/modes/HasModesIF.h"
#include "fsfw/modes/ModeHelper.h" #include "fsfw/modes/ModeHelper.h"
#include "fsfw/objectmanager/SystemObject.h" #include "fsfw/objectmanager/SystemObject.h"
#include "fsfw/subsystem/HasModeTreeChildrenIF.h"
#include "fsfw/subsystem/ModeTreeChildIF.h"
#include "fsfw/subsystem/ModeTreeConnectionIF.h"
#include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw/tasks/ExecutableObjectIF.h"
#include "fsfw/tasks/PeriodicTaskIF.h" #include "fsfw/tasks/PeriodicTaskIF.h"
@ -18,13 +21,18 @@
class ControllerBase : public HasModesIF, class ControllerBase : public HasModesIF,
public HasHealthIF, public HasHealthIF,
public ExecutableObjectIF, public ExecutableObjectIF,
public ModeTreeChildIF,
public ModeTreeConnectionIF,
public SystemObject { public SystemObject {
public: public:
static const Mode_t MODE_NORMAL = 2; static const Mode_t MODE_NORMAL = 2;
ControllerBase(object_id_t setObjectId, object_id_t parentId, size_t commandQueueDepth = 3); ControllerBase(object_id_t setObjectId, size_t commandQueueDepth = 3);
~ControllerBase() override; ~ControllerBase() override;
ReturnValue_t connectModeTreeParent(HasModeTreeChildrenIF &parent) override;
ModeTreeChildIF &getModeTreeChildIF() override;
/** SystemObject override */ /** SystemObject override */
ReturnValue_t initialize() override; ReturnValue_t initialize() override;
@ -38,6 +46,8 @@ class ControllerBase : public HasModesIF,
ReturnValue_t performOperation(uint8_t opCode) override; ReturnValue_t performOperation(uint8_t opCode) override;
void setTaskIF(PeriodicTaskIF *task) override; void setTaskIF(PeriodicTaskIF *task) override;
ReturnValue_t initializeAfterTaskCreation() override; ReturnValue_t initializeAfterTaskCreation() override;
const HasHealthIF *getOptHealthIF() const override;
const HasModesIF &getModeIF() const override;
protected: protected:
/** /**
@ -56,8 +66,6 @@ class ControllerBase : public HasModesIF,
ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode,
uint32_t *msToReachTheMode) override = 0; uint32_t *msToReachTheMode) override = 0;
const object_id_t parentId;
Mode_t mode; Mode_t mode;
Submode_t submode; Submode_t submode;

View File

@ -1,8 +1,7 @@
#include "fsfw/controller/ExtendedControllerBase.h" #include "fsfw/controller/ExtendedControllerBase.h"
ExtendedControllerBase::ExtendedControllerBase(object_id_t objectId, object_id_t parentId, ExtendedControllerBase::ExtendedControllerBase(object_id_t objectId, size_t commandQueueDepth)
size_t commandQueueDepth) : ControllerBase(objectId, commandQueueDepth),
: ControllerBase(objectId, parentId, commandQueueDepth),
poolManager(this, commandQueue), poolManager(this, commandQueue),
actionHelper(this, commandQueue) {} actionHelper(this, commandQueue) {}

View File

@ -17,7 +17,7 @@ class ExtendedControllerBase : public ControllerBase,
public HasActionsIF, public HasActionsIF,
public HasLocalDataPoolIF { public HasLocalDataPoolIF {
public: public:
ExtendedControllerBase(object_id_t objectId, object_id_t parentId, size_t commandQueueDepth = 3); ExtendedControllerBase(object_id_t objectId, size_t commandQueueDepth = 3);
~ExtendedControllerBase() override; ~ExtendedControllerBase() override;
/* SystemObjectIF overrides */ /* SystemObjectIF overrides */

View File

@ -91,7 +91,7 @@ ReturnValue_t MapPacketExtraction::unpackBlockingPackets(TcTransferFrame* frame)
while ((totalLength > ccsds::HEADER_LEN)) { while ((totalLength > ccsds::HEADER_LEN)) {
SpacePacketReader packet(position, totalLength); SpacePacketReader packet(position, totalLength);
status = packet.checkSize(); status = packet.checkSize();
if(status != returnvalue::OK) { if (status != returnvalue::OK) {
// TODO: Better error handling // TODO: Better error handling
status = DATA_CORRUPTED; status = DATA_CORRUPTED;
} }

View File

@ -70,8 +70,7 @@ ReturnValue_t LocalDataPoolManager::initialize(MessageQueueIF* queueToUse) {
return returnvalue::OK; return returnvalue::OK;
} }
ReturnValue_t LocalDataPoolManager::initializeAfterTaskCreation(uint8_t nonDiagInvlFactor) { ReturnValue_t LocalDataPoolManager::initializeAfterTaskCreation() {
setNonDiagnosticIntervalFactor(nonDiagInvlFactor);
return initializeHousekeepingPoolEntriesOnce(); return initializeHousekeepingPoolEntriesOnce();
} }
@ -506,9 +505,9 @@ ReturnValue_t LocalDataPoolManager::handleHousekeepingMessage(CommandMessage* me
float newCollIntvl = 0; float newCollIntvl = 0;
HousekeepingMessage::getCollectionIntervalModificationCommand(message, &newCollIntvl); HousekeepingMessage::getCollectionIntervalModificationCommand(message, &newCollIntvl);
if (command == HousekeepingMessage::MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL) { if (command == HousekeepingMessage::MODIFY_DIAGNOSTICS_REPORT_COLLECTION_INTERVAL) {
result = changeCollectionInterval(sid, newCollIntvl, true); result = changeCollectionInterval(sid, newCollIntvl);
} else { } else {
result = changeCollectionInterval(sid, newCollIntvl, false); result = changeCollectionInterval(sid, newCollIntvl);
} }
break; break;
} }
@ -570,6 +569,10 @@ ReturnValue_t LocalDataPoolManager::handleHousekeepingMessage(CommandMessage* me
CommandMessage reply; CommandMessage reply;
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
if (result == WRONG_HK_PACKET_TYPE) {
printWarningOrError(sif::OutputTypes::OUT_WARNING, "handleHousekeepingMessage",
WRONG_HK_PACKET_TYPE);
}
HousekeepingMessage::setHkRequestFailureReply(&reply, sid, result); HousekeepingMessage::setHkRequestFailureReply(&reply, sid, result);
} else { } else {
HousekeepingMessage::setHkRequestSuccessReply(&reply, sid); HousekeepingMessage::setHkRequestSuccessReply(&reply, sid);
@ -657,10 +660,6 @@ ReturnValue_t LocalDataPoolManager::serializeHkPacketIntoStore(HousekeepingPacke
return hkPacket.serialize(&dataPtr, serializedSize, maxSize, SerializeIF::Endianness::MACHINE); return hkPacket.serialize(&dataPtr, serializedSize, maxSize, SerializeIF::Endianness::MACHINE);
} }
void LocalDataPoolManager::setNonDiagnosticIntervalFactor(uint8_t nonDiagInvlFactor) {
this->nonDiagnosticIntervalFactor = nonDiagInvlFactor;
}
void LocalDataPoolManager::performPeriodicHkGeneration(HkReceiver& receiver) { void LocalDataPoolManager::performPeriodicHkGeneration(HkReceiver& receiver) {
sid_t sid = receiver.dataId.sid; sid_t sid = receiver.dataId.sid;
LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid);
@ -714,15 +713,15 @@ ReturnValue_t LocalDataPoolManager::togglePeriodicGeneration(sid_t sid, bool ena
if ((LocalPoolDataSetAttorney::getReportingEnabled(*dataSet) and enable) or if ((LocalPoolDataSetAttorney::getReportingEnabled(*dataSet) and enable) or
(not LocalPoolDataSetAttorney::getReportingEnabled(*dataSet) and not enable)) { (not LocalPoolDataSetAttorney::getReportingEnabled(*dataSet) and not enable)) {
return REPORTING_STATUS_UNCHANGED; return returnvalue::OK;
} }
LocalPoolDataSetAttorney::setReportingEnabled(*dataSet, enable); LocalPoolDataSetAttorney::setReportingEnabled(*dataSet, enable);
return returnvalue::OK; return returnvalue::OK;
} }
ReturnValue_t LocalDataPoolManager::changeCollectionInterval(sid_t sid, float newCollectionInterval, ReturnValue_t LocalDataPoolManager::changeCollectionInterval(sid_t sid,
bool isDiagnostics) { float newCollectionInterval) {
LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid); LocalPoolDataSetBase* dataSet = HasLocalDpIFManagerAttorney::getDataSetHandle(owner, sid);
if (dataSet == nullptr) { if (dataSet == nullptr) {
printWarningOrError(sif::OutputTypes::OUT_WARNING, "changeCollectionInterval", printWarningOrError(sif::OutputTypes::OUT_WARNING, "changeCollectionInterval",
@ -730,11 +729,6 @@ ReturnValue_t LocalDataPoolManager::changeCollectionInterval(sid_t sid, float ne
return DATASET_NOT_FOUND; return DATASET_NOT_FOUND;
} }
bool targetIsDiagnostics = LocalPoolDataSetAttorney::isDiagnostics(*dataSet);
if ((targetIsDiagnostics and not isDiagnostics) or (not targetIsDiagnostics and isDiagnostics)) {
return WRONG_HK_PACKET_TYPE;
}
PeriodicHousekeepingHelper* periodicHelper = PeriodicHousekeepingHelper* periodicHelper =
LocalPoolDataSetAttorney::getPeriodicHelper(*dataSet); LocalPoolDataSetAttorney::getPeriodicHelper(*dataSet);
@ -825,6 +819,8 @@ void LocalDataPoolManager::printWarningOrError(sif::OutputTypes outputType,
errorPrint = "Dataset not found"; errorPrint = "Dataset not found";
} else if (error == POOLOBJECT_NOT_FOUND) { } else if (error == POOLOBJECT_NOT_FOUND) {
errorPrint = "Pool Object not found"; errorPrint = "Pool Object not found";
} else if (error == WRONG_HK_PACKET_TYPE) {
errorPrint = "Wrong Packet Type";
} else if (error == returnvalue::FAILED) { } else if (error == returnvalue::FAILED) {
if (outputType == sif::OutputTypes::OUT_WARNING) { if (outputType == sif::OutputTypes::OUT_WARNING) {
errorPrint = "Generic Warning"; errorPrint = "Generic Warning";

View File

@ -102,7 +102,7 @@ class LocalDataPoolManager : public ProvidesDataPoolSubscriptionIF, public Acces
* @param nonDiagInvlFactor * @param nonDiagInvlFactor
* @return * @return
*/ */
ReturnValue_t initializeAfterTaskCreation(uint8_t nonDiagInvlFactor = 5); ReturnValue_t initializeAfterTaskCreation();
/** /**
* @brief This should be called in the periodic handler of the owner. * @brief This should be called in the periodic handler of the owner.
@ -152,17 +152,6 @@ class LocalDataPoolManager : public ProvidesDataPoolSubscriptionIF, public Acces
MessageQueueId_t targetQueueId, MessageQueueId_t targetQueueId,
bool generateSnapshot) override; bool generateSnapshot) override;
/**
* Non-Diagnostics packets usually have a lower minimum sampling frequency
* than diagnostic packets.
* A factor can be specified to determine the minimum sampling frequency
* for non-diagnostic packets. The minimum sampling frequency of the
* diagnostics packets,which is usually jusst the period of the
* performOperation calls, is multiplied with that factor.
* @param factor
*/
void setNonDiagnosticIntervalFactor(uint8_t nonDiagInvlFactor);
/** /**
* @brief The manager is also able to handle housekeeping messages. * @brief The manager is also able to handle housekeeping messages.
* @details * @details
@ -185,6 +174,7 @@ class LocalDataPoolManager : public ProvidesDataPoolSubscriptionIF, public Acces
ReturnValue_t generateHousekeepingPacket(sid_t sid, LocalPoolDataSetBase* dataSet, ReturnValue_t generateHousekeepingPacket(sid_t sid, LocalPoolDataSetBase* dataSet,
bool forDownlink, bool forDownlink,
MessageQueueId_t destination = MessageQueueIF::NO_QUEUE); MessageQueueId_t destination = MessageQueueIF::NO_QUEUE);
ReturnValue_t changeCollectionInterval(sid_t sid, float newCollectionInterval);
HasLocalDataPoolIF* getOwner(); HasLocalDataPoolIF* getOwner();
@ -348,8 +338,6 @@ class LocalDataPoolManager : public ProvidesDataPoolSubscriptionIF, public Acces
void performPeriodicHkGeneration(HkReceiver& hkReceiver); void performPeriodicHkGeneration(HkReceiver& hkReceiver);
ReturnValue_t togglePeriodicGeneration(sid_t sid, bool enable, bool isDiagnostics); ReturnValue_t togglePeriodicGeneration(sid_t sid, bool enable, bool isDiagnostics);
ReturnValue_t changeCollectionInterval(sid_t sid, float newCollectionInterval,
bool isDiagnostics);
ReturnValue_t generateSetStructurePacket(sid_t sid, bool isDiagnostics); ReturnValue_t generateSetStructurePacket(sid_t sid, bool isDiagnostics);
void handleHkUpdateResetListInsertion(DataType dataType, DataId dataId); void handleHkUpdateResetListInsertion(DataType dataType, DataId dataId);

View File

@ -250,9 +250,8 @@ void LocalPoolDataSetBase::setReportingEnabled(bool reportingEnabled) {
bool LocalPoolDataSetBase::getReportingEnabled() const { return reportingEnabled; } bool LocalPoolDataSetBase::getReportingEnabled() const { return reportingEnabled; }
void LocalPoolDataSetBase::initializePeriodicHelper(float collectionInterval, void LocalPoolDataSetBase::initializePeriodicHelper(float collectionInterval,
dur_millis_t minimumPeriodicInterval, dur_millis_t minimumPeriodicInterval) {
uint8_t nonDiagIntervalFactor) { periodicHelper->initialize(collectionInterval, minimumPeriodicInterval);
periodicHelper->initialize(collectionInterval, minimumPeriodicInterval, nonDiagIntervalFactor);
} }
void LocalPoolDataSetBase::setChanged(bool changed) { this->changed = changed; } void LocalPoolDataSetBase::setChanged(bool changed) { this->changed = changed; }

View File

@ -162,6 +162,7 @@ class LocalPoolDataSetBase : public PoolDataSetBase, public MarkChangedIF {
object_id_t getCreatorObjectId(); object_id_t getCreatorObjectId();
bool getReportingEnabled() const; bool getReportingEnabled() const;
void setReportingEnabled(bool enabled);
/** /**
* Returns the current periodic HK generation interval this set * Returns the current periodic HK generation interval this set
@ -189,10 +190,8 @@ class LocalPoolDataSetBase : public PoolDataSetBase, public MarkChangedIF {
* Used for periodic generation. * Used for periodic generation.
*/ */
bool reportingEnabled = false; bool reportingEnabled = false;
void setReportingEnabled(bool enabled);
void initializePeriodicHelper(float collectionInterval, dur_millis_t minimumPeriodicInterval, void initializePeriodicHelper(float collectionInterval, dur_millis_t minimumPeriodicInterval);
uint8_t nonDiagIntervalFactor = 5);
/** /**
* If the valid state of a dataset is always relevant to the whole * If the valid state of a dataset is always relevant to the whole

View File

@ -12,10 +12,8 @@ class LocalPoolDataSetAttorney {
static bool isDiagnostics(LocalPoolDataSetBase& set) { return set.isDiagnostics(); } static bool isDiagnostics(LocalPoolDataSetBase& set) { return set.isDiagnostics(); }
static void initializePeriodicHelper(LocalPoolDataSetBase& set, float collectionInterval, static void initializePeriodicHelper(LocalPoolDataSetBase& set, float collectionInterval,
uint32_t minimumPeriodicIntervalMs, uint32_t minimumPeriodicIntervalMs) {
uint8_t nonDiagIntervalFactor = 5) { set.initializePeriodicHelper(collectionInterval, minimumPeriodicIntervalMs);
set.initializePeriodicHelper(collectionInterval, minimumPeriodicIntervalMs,
nonDiagIntervalFactor);
} }
static void setReportingEnabled(LocalPoolDataSetBase& set, bool enabled) { static void setReportingEnabled(LocalPoolDataSetBase& set, bool enabled) {

View File

@ -1,7 +1,7 @@
#include "fsfw/devicehandlers/AssemblyBase.h" #include "fsfw/devicehandlers/AssemblyBase.h"
AssemblyBase::AssemblyBase(object_id_t objectId, object_id_t parentId, uint16_t commandQueueDepth) AssemblyBase::AssemblyBase(object_id_t objectId, uint16_t commandQueueDepth)
: SubsystemBase(objectId, parentId, MODE_OFF, commandQueueDepth), : SubsystemBase(objectId, MODE_OFF, commandQueueDepth),
internalState(STATE_NONE), internalState(STATE_NONE),
recoveryState(RECOVERY_IDLE), recoveryState(RECOVERY_IDLE),
recoveringDevice(childrenMap.end()), recoveringDevice(childrenMap.end()),
@ -26,11 +26,7 @@ void AssemblyBase::performChildOperation() {
void AssemblyBase::startTransition(Mode_t mode, Submode_t submode) { void AssemblyBase::startTransition(Mode_t mode, Submode_t submode) {
doStartTransition(mode, submode); doStartTransition(mode, submode);
if (modeHelper.isForced()) { triggerModeHelperEvents(mode, submode);
triggerEvent(FORCING_MODE, mode, submode);
} else {
triggerEvent(CHANGING_MODE, mode, submode);
}
} }
void AssemblyBase::doStartTransition(Mode_t mode, Submode_t submode) { void AssemblyBase::doStartTransition(Mode_t mode, Submode_t submode) {
@ -77,9 +73,10 @@ bool AssemblyBase::handleChildrenChangedHealth() {
} }
HealthState healthState = healthHelper.healthTable->getHealth(iter->first); HealthState healthState = healthHelper.healthTable->getHealth(iter->first);
if (healthState == HasHealthIF::NEEDS_RECOVERY) { if (healthState == HasHealthIF::NEEDS_RECOVERY) {
triggerEvent(TRYING_RECOVERY); triggerEvent(TRYING_RECOVERY, iter->first, 0);
recoveryState = RECOVERY_STARTED; recoveryState = RECOVERY_STARTED;
recoveringDevice = iter; recoveringDevice = iter;
// The user needs to take care of commanding the children off in commandChildren
doStartTransition(targetMode, targetSubmode); doStartTransition(targetMode, targetSubmode);
} else { } else {
triggerEvent(CHILD_CHANGED_HEALTH); triggerEvent(CHILD_CHANGED_HEALTH);
@ -228,6 +225,9 @@ ReturnValue_t AssemblyBase::handleHealthReply(CommandMessage* message) {
bool AssemblyBase::checkAndHandleRecovery() { bool AssemblyBase::checkAndHandleRecovery() {
switch (recoveryState) { switch (recoveryState) {
case RECOVERY_STARTED: case RECOVERY_STARTED:
// The recovery was already start in #handleChildrenChangedHealth and we just need
// to wait for an off time period.
// TODO: make time period configurable
recoveryState = RECOVERY_WAIT; recoveryState = RECOVERY_WAIT;
recoveryOffTimer.resetTimer(); recoveryOffTimer.resetTimer();
return true; return true;
@ -266,3 +266,11 @@ void AssemblyBase::overwriteDeviceHealth(object_id_t objectId, HasHealthIF::Heal
modeHelper.setForced(true); modeHelper.setForced(true);
sendHealthCommand(childrenMap[objectId].commandQueue, EXTERNAL_CONTROL); sendHealthCommand(childrenMap[objectId].commandQueue, EXTERNAL_CONTROL);
} }
void AssemblyBase::triggerModeHelperEvents(Mode_t mode, Submode_t submode) {
if (modeHelper.isForced()) {
triggerEvent(FORCING_MODE, mode, submode);
} else {
triggerEvent(CHANGING_MODE, mode, submode);
}
}

View File

@ -12,7 +12,8 @@
* Documentation: Dissertation Baetz p.156, 157. * Documentation: Dissertation Baetz p.156, 157.
* *
* This class reduces the complexity of controller components which would * This class reduces the complexity of controller components which would
* otherwise be needed for the handling of redundant devices. * otherwise be needed for the handling of redundant devices. However, it can also be used to
* manage the mode keeping and recovery of non-redundant devices
* *
* The template class monitors mode and health state of its children * The template class monitors mode and health state of its children
* and checks availability of devices on every detected change. * and checks availability of devices on every detected change.
@ -26,11 +27,9 @@
* *
* Important: * Important:
* *
* The implementation must call registerChild(object_id_t child) * The implementation must call #registerChild for all commanded children during initialization.
* for all commanded children during initialization.
* The implementation must call the initialization function of the base class. * The implementation must call the initialization function of the base class.
* (This will call the function in SubsystemBase) * (This will call the function in SubsystemBase)
*
*/ */
class AssemblyBase : public SubsystemBase { class AssemblyBase : public SubsystemBase {
public: public:
@ -42,14 +41,15 @@ class AssemblyBase : public SubsystemBase {
static const ReturnValue_t NEED_TO_CHANGE_HEALTH = MAKE_RETURN_CODE(0x05); static const ReturnValue_t NEED_TO_CHANGE_HEALTH = MAKE_RETURN_CODE(0x05);
static const ReturnValue_t NOT_ENOUGH_CHILDREN_IN_CORRECT_STATE = MAKE_RETURN_CODE(0xa1); static const ReturnValue_t NOT_ENOUGH_CHILDREN_IN_CORRECT_STATE = MAKE_RETURN_CODE(0xa1);
AssemblyBase(object_id_t objectId, object_id_t parentId, uint16_t commandQueueDepth = 8); AssemblyBase(object_id_t objectId, uint16_t commandQueueDepth = 8);
virtual ~AssemblyBase(); virtual ~AssemblyBase();
protected: protected:
/** /**
* Command children to reach [mode,submode] combination * Command children to reach [mode,submode] combination. Can be done by setting
* Can be done by setting #commandsOutstanding correctly, * #commandsOutstanding correctly, or using #executeTable. In case of an FDIR recovery,
* or using executeTable() * the user needs to ensure that the target devices are healthy. If a device is not healthy,
* a recovery might be on-going and the device needs to be commanded to off first.
* @param mode * @param mode
* @param submode * @param submode
* @return * @return
@ -120,8 +120,19 @@ class AssemblyBase : public SubsystemBase {
virtual ReturnValue_t handleHealthReply(CommandMessage *message); virtual ReturnValue_t handleHealthReply(CommandMessage *message);
virtual void performChildOperation(); /**
* @brief Default periodic handler
* @details
* This is the default periodic handler which will be called by the SubsystemBase
* performOperation. It performs the child transitions or reacts to changed health/mode states
* of children objects
*/
virtual void performChildOperation() override;
/**
* This function handles changed mode or health states of children
* @return
*/
bool handleChildrenChanged(); bool handleChildrenChanged();
/** /**
@ -134,12 +145,37 @@ class AssemblyBase : public SubsystemBase {
bool handleChildrenChangedHealth(); bool handleChildrenChangedHealth();
/**
* Core transition handler. The default implementation will only do something if
* #commandsOutstanding is smaller or equal to zero, which means that all mode commands
* from the #doPerformTransition call were executed successfully.
*
* Unless a second step was requested, the function will then use #checkChildrenState to
* determine whether the target mode was reached.
*
* There is some special handling for certain (internal) modes:
* - A second step is necessary. #commandChildren will be performed again
* - The device health was overwritten. #commandChildren will be called
* - A recovery is ongoing. #checkAndHandleRecovery will be called.
*/
virtual void handleChildrenTransition(); virtual void handleChildrenTransition();
ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, uint32_t *msToReachTheMode); ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, uint32_t *msToReachTheMode);
/**
* Calls #doStartTransition and triggers an informative event as well that the mode will
* change
* @param mode
* @param submode
*/
virtual void startTransition(Mode_t mode, Submode_t submode); virtual void startTransition(Mode_t mode, Submode_t submode);
/**
* This function starts the transition by setting the internal #targetSubmode and #targetMode
* variables and then calling the #commandChildren function.
* @param mode
* @param submode
*/
virtual void doStartTransition(Mode_t mode, Submode_t submode); virtual void doStartTransition(Mode_t mode, Submode_t submode);
virtual bool isInTransition(); virtual bool isInTransition();
@ -160,7 +196,7 @@ class AssemblyBase : public SubsystemBase {
* Manages recovery of a device * Manages recovery of a device
* @return true if recovery is still ongoing, false else. * @return true if recovery is still ongoing, false else.
*/ */
bool checkAndHandleRecovery(); virtual bool checkAndHandleRecovery();
/** /**
* Helper method to overwrite health state of one of the children. * Helper method to overwrite health state of one of the children.
@ -168,6 +204,8 @@ class AssemblyBase : public SubsystemBase {
* @param objectId Must be a registered child. * @param objectId Must be a registered child.
*/ */
void overwriteDeviceHealth(object_id_t objectId, HasHealthIF::HealthState oldHealth); void overwriteDeviceHealth(object_id_t objectId, HasHealthIF::HealthState oldHealth);
void triggerModeHelperEvents(Mode_t mode, Submode_t submode);
}; };
#endif /* FSFW_DEVICEHANDLERS_ASSEMBLYBASE_H_ */ #endif /* FSFW_DEVICEHANDLERS_ASSEMBLYBASE_H_ */

View File

@ -3,17 +3,12 @@
#include "fsfw/subsystem/SubsystemBase.h" #include "fsfw/subsystem/SubsystemBase.h"
ChildHandlerBase::ChildHandlerBase(object_id_t setObjectId, object_id_t deviceCommunication, ChildHandlerBase::ChildHandlerBase(object_id_t setObjectId, object_id_t deviceCommunication,
CookieIF* cookie, object_id_t hkDestination, CookieIF* cookie, HasModeTreeChildrenIF& parent,
uint32_t thermalStatePoolId, uint32_t thermalRequestPoolId, FailureIsolationBase* customFdir, size_t cmdQueueSize)
object_id_t parent, FailureIsolationBase* customFdir,
size_t cmdQueueSize)
: DeviceHandlerBase(setObjectId, deviceCommunication, cookie, : DeviceHandlerBase(setObjectId, deviceCommunication, cookie,
(customFdir == nullptr ? &childHandlerFdir : customFdir), cmdQueueSize), (customFdir == nullptr ? &childHandlerFdir : customFdir), cmdQueueSize),
parentId(parent), parent(parent),
childHandlerFdir(setObjectId) { childHandlerFdir(setObjectId) {}
this->setHkDestination(hkDestination);
this->setThermalStateRequestPoolIds(thermalStatePoolId, thermalRequestPoolId);
}
ChildHandlerBase::~ChildHandlerBase() {} ChildHandlerBase::~ChildHandlerBase() {}
@ -23,21 +18,5 @@ ReturnValue_t ChildHandlerBase::initialize() {
return result; return result;
} }
MessageQueueId_t parentQueue = 0; return DeviceHandlerBase::connectModeTreeParent(parent);
if (parentId != objects::NO_OBJECT) {
SubsystemBase* parent = ObjectManager::instance()->get<SubsystemBase>(parentId);
if (parent == NULL) {
return returnvalue::FAILED;
}
parentQueue = parent->getCommandQueue();
parent->registerChild(getObjectId());
}
healthHelper.setParentQueue(parentQueue);
modeHelper.setParentQueue(parentQueue);
return returnvalue::OK;
} }

View File

@ -1,22 +1,23 @@
#ifndef FSFW_DEVICEHANDLER_CHILDHANDLERBASE_H_ #ifndef FSFW_DEVICEHANDLER_CHILDHANDLERBASE_H_
#define FSFW_DEVICEHANDLER_CHILDHANDLERBASE_H_ #define FSFW_DEVICEHANDLER_CHILDHANDLERBASE_H_
#include <fsfw/subsystem/HasModeTreeChildrenIF.h>
#include "ChildHandlerFDIR.h" #include "ChildHandlerFDIR.h"
#include "DeviceHandlerBase.h" #include "DeviceHandlerBase.h"
class ChildHandlerBase : public DeviceHandlerBase { class ChildHandlerBase : public DeviceHandlerBase {
public: public:
ChildHandlerBase(object_id_t setObjectId, object_id_t deviceCommunication, CookieIF* cookie, ChildHandlerBase(object_id_t setObjectId, object_id_t deviceCommunication, CookieIF* cookie,
object_id_t hkDestination, uint32_t thermalStatePoolId, HasModeTreeChildrenIF& parent, FailureIsolationBase* customFdir = nullptr,
uint32_t thermalRequestPoolId, object_id_t parent = objects::NO_OBJECT, size_t cmdQueueSize = 20);
FailureIsolationBase* customFdir = nullptr, size_t cmdQueueSize = 20);
virtual ~ChildHandlerBase(); virtual ~ChildHandlerBase();
virtual ReturnValue_t initialize(); virtual ReturnValue_t initialize();
protected: protected:
const uint32_t parentId; HasModeTreeChildrenIF& parent;
ChildHandlerFDIR childHandlerFdir; ChildHandlerFDIR childHandlerFdir;
}; };

View File

@ -49,6 +49,7 @@ class DeviceCommunicationIF {
// is this needed if there is no open/close call? // is this needed if there is no open/close call?
static const ReturnValue_t NOT_ACTIVE = MAKE_RETURN_CODE(0x05); static const ReturnValue_t NOT_ACTIVE = MAKE_RETURN_CODE(0x05);
static const ReturnValue_t TOO_MUCH_DATA = MAKE_RETURN_CODE(0x06); static const ReturnValue_t TOO_MUCH_DATA = MAKE_RETURN_CODE(0x06);
static constexpr ReturnValue_t BUSY = MAKE_RETURN_CODE(0x07);
virtual ~DeviceCommunicationIF() {} virtual ~DeviceCommunicationIF() {}

View File

@ -1,4 +1,4 @@
#include "fsfw/devicehandlers/DeviceHandlerBase.h" #include "DeviceHandlerBase.h"
#include "fsfw/datapool/PoolReadGuard.h" #include "fsfw/datapool/PoolReadGuard.h"
#include "fsfw/datapoollocal/LocalPoolVariable.h" #include "fsfw/datapoollocal/LocalPoolVariable.h"
@ -13,6 +13,7 @@
#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/serviceinterface/ServiceInterface.h"
#include "fsfw/storagemanager/StorageManagerIF.h" #include "fsfw/storagemanager/StorageManagerIF.h"
#include "fsfw/subsystem/SubsystemBase.h" #include "fsfw/subsystem/SubsystemBase.h"
#include "fsfw/subsystem/helper.h"
#include "fsfw/thermal/ThermalComponentIF.h" #include "fsfw/thermal/ThermalComponentIF.h"
object_id_t DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT; object_id_t DeviceHandlerBase::powerSwitcherId = objects::NO_OBJECT;
@ -23,8 +24,6 @@ DeviceHandlerBase::DeviceHandlerBase(object_id_t setObjectId, object_id_t device
CookieIF* comCookie, FailureIsolationBase* fdirInstance, CookieIF* comCookie, FailureIsolationBase* fdirInstance,
size_t cmdQueueSize) size_t cmdQueueSize)
: SystemObject(setObjectId), : SystemObject(setObjectId),
mode(MODE_OFF),
submode(SUBMODE_NONE),
wiretappingMode(OFF), wiretappingMode(OFF),
storedRawData(StorageManagerIF::INVALID_ADDRESS), storedRawData(StorageManagerIF::INVALID_ADDRESS),
deviceCommunicationId(deviceCommunication), deviceCommunicationId(deviceCommunication),
@ -39,10 +38,13 @@ DeviceHandlerBase::DeviceHandlerBase(object_id_t setObjectId, object_id_t device
defaultFDIRUsed(fdirInstance == nullptr), defaultFDIRUsed(fdirInstance == nullptr),
switchOffWasReported(false), switchOffWasReported(false),
childTransitionDelay(5000), childTransitionDelay(5000),
mode(MODE_OFF),
submode(SUBMODE_NONE),
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();
@ -50,21 +52,13 @@ DeviceHandlerBase::DeviceHandlerBase(object_id_t setObjectId, object_id_t device
printWarningOrError(sif::OutputTypes::OUT_ERROR, "DeviceHandlerBase", returnvalue::FAILED, printWarningOrError(sif::OutputTypes::OUT_ERROR, "DeviceHandlerBase", returnvalue::FAILED,
"Invalid cookie"); "Invalid cookie");
} }
if (this->fdirInstance == nullptr) {
this->fdirInstance = new DeviceHandlerFailureIsolation(setObjectId, defaultFdirParentId);
}
} }
void DeviceHandlerBase::setHkDestination(object_id_t hkDestination) { void DeviceHandlerBase::setHkDestination(object_id_t hkDestination) {
this->hkDestination = hkDestination; this->hkDestination = hkDestination;
} }
void DeviceHandlerBase::setThermalStateRequestPoolIds(lp_id_t thermalStatePoolId, void DeviceHandlerBase::enableThermalModule(ThermalStateCfg cfg) { this->thermalStateCfg = cfg; }
lp_id_t heaterRequestPoolId,
uint32_t thermalSetId) {
thermalSet =
new DeviceHandlerThermalSet(this, thermalSetId, thermalStatePoolId, heaterRequestPoolId);
}
DeviceHandlerBase::~DeviceHandlerBase() { DeviceHandlerBase::~DeviceHandlerBase() {
if (comCookie != nullptr) { if (comCookie != nullptr) {
@ -130,6 +124,10 @@ ReturnValue_t DeviceHandlerBase::initialize() {
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
return result; return result;
} }
if (this->fdirInstance == nullptr) {
this->fdirInstance =
new DeviceHandlerFailureIsolation(this->getObjectId(), defaultFdirParentId);
}
communicationInterface = communicationInterface =
ObjectManager::instance()->get<DeviceCommunicationIF>(deviceCommunicationId); ObjectManager::instance()->get<DeviceCommunicationIF>(deviceCommunicationId);
@ -224,12 +222,11 @@ ReturnValue_t DeviceHandlerBase::initialize() {
fillCommandAndReplyMap(); fillCommandAndReplyMap();
if (thermalSet != nullptr) { if (thermalSet != nullptr) {
PoolReadGuard pg(thermalSet);
// Set temperature target state to NON_OP. // Set temperature target state to NON_OP.
result = thermalSet->read(); if (pg.getReadResult() == returnvalue::OK) {
if (result == returnvalue::OK) {
thermalSet->heaterRequest.value = ThermalComponentIF::STATE_REQUEST_NON_OPERATIONAL; thermalSet->heaterRequest.value = ThermalComponentIF::STATE_REQUEST_NON_OPERATIONAL;
thermalSet->heaterRequest.setValid(true); thermalSet->heaterRequest.setValid(true);
thermalSet->commit();
} }
} }
@ -353,7 +350,6 @@ void DeviceHandlerBase::doStateMachine() {
currentUptime - timeoutStart >= powerSwitcher->getSwitchDelayMs()) { currentUptime - timeoutStart >= powerSwitcher->getSwitchDelayMs()) {
triggerEvent(MODE_TRANSITION_FAILED, PowerSwitchIF::SWITCH_TIMEOUT, 0); triggerEvent(MODE_TRANSITION_FAILED, PowerSwitchIF::SWITCH_TIMEOUT, 0);
setMode(_MODE_POWER_DOWN); setMode(_MODE_POWER_DOWN);
callChildStatemachine();
break; break;
} }
ReturnValue_t switchState = getStateOfSwitches(); ReturnValue_t switchState = getStateOfSwitches();
@ -367,13 +363,12 @@ void DeviceHandlerBase::doStateMachine() {
} }
} break; } break;
case _MODE_WAIT_OFF: { case _MODE_WAIT_OFF: {
uint32_t currentUptime;
Clock::getUptime(&currentUptime);
if (powerSwitcher == nullptr) { if (powerSwitcher == nullptr) {
setMode(MODE_OFF); setMode(MODE_OFF);
break; break;
} }
uint32_t currentUptime;
Clock::getUptime(&currentUptime);
if (currentUptime - timeoutStart >= powerSwitcher->getSwitchDelayMs()) { if (currentUptime - timeoutStart >= powerSwitcher->getSwitchDelayMs()) {
triggerEvent(MODE_TRANSITION_FAILED, PowerSwitchIF::SWITCH_TIMEOUT, 0); triggerEvent(MODE_TRANSITION_FAILED, PowerSwitchIF::SWITCH_TIMEOUT, 0);
setMode(MODE_ERROR_ON); setMode(MODE_ERROR_ON);
@ -381,7 +376,7 @@ void DeviceHandlerBase::doStateMachine() {
} }
ReturnValue_t switchState = getStateOfSwitches(); ReturnValue_t switchState = getStateOfSwitches();
if ((switchState == PowerSwitchIF::SWITCH_OFF) || (switchState == NO_SWITCH)) { if ((switchState == PowerSwitchIF::SWITCH_OFF) || (switchState == NO_SWITCH)) {
setMode(_MODE_SWITCH_IS_OFF); setMode(MODE_OFF, SUBMODE_NONE);
} }
} break; } break;
case MODE_OFF: case MODE_OFF:
@ -394,9 +389,6 @@ void DeviceHandlerBase::doStateMachine() {
case MODE_NORMAL: case MODE_NORMAL:
case MODE_ERROR_ON: case MODE_ERROR_ON:
break; break;
case _MODE_SWITCH_IS_OFF:
setMode(MODE_OFF, SUBMODE_NONE);
break;
default: default:
triggerEvent(OBJECT_IN_INVALID_MODE, mode, submode); triggerEvent(OBJECT_IN_INVALID_MODE, mode, submode);
setMode(_MODE_POWER_DOWN, 0); setMode(_MODE_POWER_DOWN, 0);
@ -568,25 +560,40 @@ void DeviceHandlerBase::setTransition(Mode_t modeTo, Submode_t submodeTo) {
} }
void DeviceHandlerBase::setMode(Mode_t newMode, uint8_t newSubmode) { void DeviceHandlerBase::setMode(Mode_t newMode, uint8_t newSubmode) {
/* TODO: This will probably be done by the LocalDataPoolManager now */ /**
// changeHK(mode, submode, false); * handle transition from OFF to NORMAL by continuing towards normal when ON is reached
*/
if (newMode == MODE_ON and continueToNormal) {
continueToNormal = false;
// TODO: Check whether the following two lines are okay to do so.
transitionSourceMode = MODE_ON;
transitionSourceSubMode = newSubmode;
mode = _MODE_TO_NORMAL;
return;
}
submode = newSubmode; submode = newSubmode;
mode = newMode; mode = newMode;
modeChanged(); modeChanged();
setNormalDatapoolEntriesInvalid(); setNormalDatapoolEntriesInvalid();
if (newMode == MODE_OFF) {
disableCommandsAndReplies();
}
if (!isTransitionalMode()) { if (!isTransitionalMode()) {
// clear this flag when a non-transitional Mode is reached to be safe
continueToNormal = false;
modeHelper.modeChanged(newMode, newSubmode); modeHelper.modeChanged(newMode, newSubmode);
announceMode(false); announceMode(false);
} }
Clock::getUptime(&timeoutStart); Clock::getUptime(&timeoutStart);
if (mode == MODE_OFF and thermalSet != nullptr) { if (mode == MODE_OFF and thermalSet != nullptr) {
ReturnValue_t result = thermalSet->read(); PoolReadGuard pg(thermalSet);
if (result == returnvalue::OK) { if (pg.getReadResult() == returnvalue::OK) {
if (thermalSet->heaterRequest.value != ThermalComponentIF::STATE_REQUEST_IGNORE) { if (thermalSet->heaterRequest.value != ThermalComponentIF::STATE_REQUEST_IGNORE) {
thermalSet->heaterRequest.value = ThermalComponentIF::STATE_REQUEST_NON_OPERATIONAL; thermalSet->heaterRequest.value = ThermalComponentIF::STATE_REQUEST_NON_OPERATIONAL;
} }
thermalSet->heaterRequest.commit(PoolVariableIF::VALID); thermalSet->heaterRequest.setValid(true);
} }
} }
/* TODO: This will probably be done by the LocalDataPoolManager now */ /* TODO: This will probably be done by the LocalDataPoolManager now */
@ -1059,8 +1066,7 @@ Mode_t DeviceHandlerBase::getBaseMode(Mode_t transitionMode) {
return transitionMode & ~(TRANSITION_MODE_BASE_ACTION_MASK | TRANSITION_MODE_CHILD_ACTION_MASK); return transitionMode & ~(TRANSITION_MODE_BASE_ACTION_MASK | TRANSITION_MODE_CHILD_ACTION_MASK);
} }
// SHOULDDO: Allow transition from OFF to NORMAL to reduce complexity in assemblies. And, by the // SHOULDDO: throw away DHB and write a new one:
// way, throw away DHB and write a new one:
// - Include power and thermal completely, but more modular :-) // - Include power and thermal completely, but more modular :-)
// - Don't use modes for state transitions, reduce FSM (Finte State Machine) complexity. // - Don't use modes for state transitions, reduce FSM (Finte State Machine) complexity.
// - Modularization? // - Modularization?
@ -1072,13 +1078,12 @@ ReturnValue_t DeviceHandlerBase::checkModeCommand(Mode_t commandedMode, Submode_
if ((mode == MODE_ERROR_ON) && (commandedMode != MODE_OFF)) { if ((mode == MODE_ERROR_ON) && (commandedMode != MODE_OFF)) {
return TRANS_NOT_ALLOWED; return TRANS_NOT_ALLOWED;
} }
if ((commandedMode == MODE_NORMAL) && (mode == MODE_OFF)) {
return TRANS_NOT_ALLOWED;
}
if ((commandedMode == MODE_ON) && (mode == MODE_OFF) and (thermalSet != nullptr)) { // Do not check thermal state for MODE_RAW
ReturnValue_t result = thermalSet->read(); if ((mode == MODE_OFF) and ((commandedMode == MODE_ON) or (commandedMode == MODE_NORMAL)) and
if (result == returnvalue::OK) { (thermalSet != nullptr)) {
PoolReadGuard pg(thermalSet);
if (pg.getReadResult() == returnvalue::OK) {
if ((thermalSet->heaterRequest.value != ThermalComponentIF::STATE_REQUEST_IGNORE) and if ((thermalSet->heaterRequest.value != ThermalComponentIF::STATE_REQUEST_IGNORE) and
(not ThermalComponentIF::isOperational(thermalSet->thermalState.value))) { (not ThermalComponentIF::isOperational(thermalSet->thermalState.value))) {
triggerEvent(ThermalComponentIF::TEMP_NOT_IN_OP_RANGE, thermalSet->thermalState.value); triggerEvent(ThermalComponentIF::TEMP_NOT_IN_OP_RANGE, thermalSet->thermalState.value);
@ -1091,6 +1096,7 @@ ReturnValue_t DeviceHandlerBase::checkModeCommand(Mode_t commandedMode, Submode_
} }
void DeviceHandlerBase::startTransition(Mode_t commandedMode, Submode_t commandedSubmode) { void DeviceHandlerBase::startTransition(Mode_t commandedMode, Submode_t commandedSubmode) {
continueToNormal = false;
switch (commandedMode) { switch (commandedMode) {
case MODE_ON: case MODE_ON:
handleTransitionToOnMode(commandedMode, commandedSubmode); handleTransitionToOnMode(commandedMode, commandedSubmode);
@ -1120,8 +1126,9 @@ void DeviceHandlerBase::startTransition(Mode_t commandedMode, Submode_t commande
case MODE_NORMAL: case MODE_NORMAL:
if (mode != MODE_OFF) { if (mode != MODE_OFF) {
setTransition(MODE_NORMAL, commandedSubmode); setTransition(MODE_NORMAL, commandedSubmode);
} else { } else { // mode is off
replyReturnvalueToCommand(HasModesIF::TRANS_NOT_ALLOWED); continueToNormal = true;
handleTransitionToOnMode(MODE_NORMAL, commandedSubmode);
} }
break; break;
} }
@ -1137,11 +1144,10 @@ void DeviceHandlerBase::handleTransitionToOnMode(Mode_t commandedMode, Submode_t
childTransitionDelay = getTransitionDelayMs(_MODE_START_UP, MODE_ON); childTransitionDelay = getTransitionDelayMs(_MODE_START_UP, MODE_ON);
triggerEvent(CHANGING_MODE, commandedMode, commandedSubmode); triggerEvent(CHANGING_MODE, commandedMode, commandedSubmode);
if (thermalSet != nullptr) { if (thermalSet != nullptr) {
ReturnValue_t result = thermalSet->read(); PoolReadGuard pg(thermalSet);
if (result == returnvalue::OK) { if (pg.getReadResult() == returnvalue::OK) {
if (thermalSet->heaterRequest != ThermalComponentIF::STATE_REQUEST_IGNORE) { if (thermalSet->heaterRequest != ThermalComponentIF::STATE_REQUEST_IGNORE) {
thermalSet->heaterRequest = ThermalComponentIF::STATE_REQUEST_OPERATIONAL; thermalSet->heaterRequest = ThermalComponentIF::STATE_REQUEST_OPERATIONAL;
thermalSet->commit();
} }
} }
} }
@ -1279,6 +1285,7 @@ void DeviceHandlerBase::handleDeviceTm(const SerializeIF& dataSet, DeviceCommand
if (iter->second.command != deviceCommandMap.end()) { if (iter->second.command != deviceCommandMap.end()) {
MessageQueueId_t queueId = iter->second.command->second.sendReplyTo; MessageQueueId_t queueId = iter->second.command->second.sendReplyTo;
// This may fail, but we'll ignore the fault.
if (queueId != NO_COMMANDER) { if (queueId != NO_COMMANDER) {
// This may fail, but we'll ignore the fault. // This may fail, but we'll ignore the fault.
actionHelper.reportData(queueId, replyId, const_cast<SerializeIF*>(&dataSet)); actionHelper.reportData(queueId, replyId, const_cast<SerializeIF*>(&dataSet));
@ -1457,15 +1464,17 @@ 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,
LocalDataPoolManager& poolManager) { LocalDataPoolManager& poolManager) {
if (thermalSet != nullptr) { if (thermalStateCfg.has_value()) {
localDataPoolMap.emplace(thermalSet->thermalStatePoolId, localDataPoolMap.emplace(thermalStateCfg.value().thermalStatePoolId,
new PoolEntry<DeviceHandlerIF::dh_thermal_state_t>); new PoolEntry<DeviceHandlerIF::dh_thermal_state_t>());
localDataPoolMap.emplace(thermalSet->heaterRequestPoolId, localDataPoolMap.emplace(thermalStateCfg.value().thermalRequestPoolId,
new PoolEntry<DeviceHandlerIF::dh_heater_request_t>); new PoolEntry<DeviceHandlerIF::dh_heater_request_t>());
} }
return returnvalue::OK; return returnvalue::OK;
} }
@ -1478,8 +1487,12 @@ ReturnValue_t DeviceHandlerBase::initializeAfterTaskCreation() {
} }
this->poolManager.initializeAfterTaskCreation(); this->poolManager.initializeAfterTaskCreation();
if (thermalStateCfg.has_value()) {
ThermalStateCfg& cfg = thermalStateCfg.value();
thermalSet = new DeviceHandlerThermalSet(this, cfg);
}
if (setStartupImmediately) { if (setStartupImmediately) {
startTransition(MODE_ON, SUBMODE_NONE); startTransition(MODE_ON, getInitialSubmode());
} }
return returnvalue::OK; return returnvalue::OK;
} }
@ -1566,3 +1579,52 @@ MessageQueueId_t DeviceHandlerBase::getCommanderQueueId(DeviceCommandId_t replyI
} }
return commandIter->second.sendReplyTo; return commandIter->second.sendReplyTo;
} }
void DeviceHandlerBase::setCustomFdir(FailureIsolationBase* fdir) { this->fdirInstance = fdir; }
void DeviceHandlerBase::setPowerSwitcher(PowerSwitchIF* switcher) {
this->powerSwitcher = switcher;
}
Mode_t DeviceHandlerBase::getMode() { return mode; }
Submode_t DeviceHandlerBase::getSubmode() { return submode; }
void DeviceHandlerBase::disableCommandsAndReplies() {
for (auto& command : deviceCommandMap) {
if (command.second.isExecuting) {
command.second.isExecuting = false;
}
}
for (auto& reply : deviceReplyMap) {
if (!reply.second.periodic) {
if (reply.second.countdown != nullptr) {
reply.second.countdown->timeOut();
} else {
reply.second.delayCycles = 0;
}
reply.second.active = false;
}
}
}
ReturnValue_t DeviceHandlerBase::connectModeTreeParent(HasModeTreeChildrenIF& parent) {
return modetree::connectModeTreeParent(parent, *this, &healthHelper, modeHelper);
}
const HasHealthIF* DeviceHandlerBase::getOptHealthIF() const { return this; }
const HasModesIF& DeviceHandlerBase::getModeIF() const { return *this; }
ModeTreeChildIF& DeviceHandlerBase::getModeTreeChildIF() { return *this; }
ReturnValue_t DeviceHandlerBase::finishAction(bool success, DeviceCommandId_t action,
ReturnValue_t result) {
auto commandIter = deviceCommandMap.find(action);
if (commandIter == deviceCommandMap.end()) {
return MessageQueueIF::NO_QUEUE;
}
commandIter->second.isExecuting = false;
actionHelper.finish(success, commandIter->second.sendReplyTo, action, result);
return returnvalue::OK;
}

View File

@ -2,6 +2,7 @@
#define FSFW_DEVICEHANDLERS_DEVICEHANDLERBASE_H_ #define FSFW_DEVICEHANDLERS_DEVICEHANDLERBASE_H_
#include <map> #include <map>
#include <optional>
#include "DeviceCommunicationIF.h" #include "DeviceCommunicationIF.h"
#include "DeviceHandlerFailureIsolation.h" #include "DeviceHandlerFailureIsolation.h"
@ -21,6 +22,7 @@
#include "fsfw/returnvalues/returnvalue.h" #include "fsfw/returnvalues/returnvalue.h"
#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/serviceinterface/ServiceInterface.h"
#include "fsfw/serviceinterface/serviceInterfaceDefintions.h" #include "fsfw/serviceinterface/serviceInterfaceDefintions.h"
#include "fsfw/subsystem/ModeTreeConnectionIF.h"
#include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw/tasks/ExecutableObjectIF.h"
#include "fsfw/tasks/PeriodicTaskIF.h" #include "fsfw/tasks/PeriodicTaskIF.h"
@ -83,6 +85,8 @@ class DeviceHandlerBase : public DeviceHandlerIF,
public HasModesIF, public HasModesIF,
public HasHealthIF, public HasHealthIF,
public HasActionsIF, public HasActionsIF,
public ModeTreeChildIF,
public ModeTreeConnectionIF,
public ReceivesParameterMessagesIF, public ReceivesParameterMessagesIF,
public HasLocalDataPoolIF { public HasLocalDataPoolIF {
friend void(Factory::setStaticFrameworkObjectIds)(); friend void(Factory::setStaticFrameworkObjectIds)();
@ -102,6 +106,51 @@ class DeviceHandlerBase : public DeviceHandlerIF,
DeviceHandlerBase(object_id_t setObjectId, object_id_t deviceCommunication, CookieIF *comCookie, DeviceHandlerBase(object_id_t setObjectId, object_id_t deviceCommunication, CookieIF *comCookie,
FailureIsolationBase *fdirInstance = nullptr, size_t cmdQueueSize = 20); FailureIsolationBase *fdirInstance = nullptr, size_t cmdQueueSize = 20);
void setCustomFdir(FailureIsolationBase *fdir);
void setPowerSwitcher(PowerSwitchIF *switcher);
/**
* extending the modes of DeviceHandler IF for internal state machine
*/
static constexpr uint8_t TRANSITION_MODE_CHILD_ACTION_MASK = 0x20;
static constexpr uint8_t TRANSITION_MODE_BASE_ACTION_MASK = 0x10;
//! This is a transitional state which can not be commanded. The device
//! handler performs all commands to get the device in a state ready to
//! perform commands. When this is completed, the mode changes to @c MODE_ON.
static const Mode_t _MODE_START_UP = TRANSITION_MODE_CHILD_ACTION_MASK | 5;
//! This is a transitional state which can not be commanded.
//! The device handler performs all actions and commands to get the device
//! shut down. When the device is off, the mode changes to @c MODE_OFF.
//! It is possible to set the mode to _MODE_SHUT_DOWN to use the to off
//! transition if available.
static const Mode_t _MODE_SHUT_DOWN = TRANSITION_MODE_CHILD_ACTION_MASK | 6;
//! It is possible to set the mode to _MODE_TO_ON to use the to on
//! transition if available.
static const Mode_t _MODE_TO_ON = TRANSITION_MODE_CHILD_ACTION_MASK | HasModesIF::MODE_ON;
//! It is possible to set the mode to _MODE_TO_RAW to use the to raw
//! transition if available.
static const Mode_t _MODE_TO_RAW = TRANSITION_MODE_CHILD_ACTION_MASK | MODE_RAW;
//! It is possible to set the mode to _MODE_TO_NORMAL to use the to normal
//! transition if available.
static const Mode_t _MODE_TO_NORMAL = TRANSITION_MODE_CHILD_ACTION_MASK | MODE_NORMAL;
//! This is a transitional state which can not be commanded.
//! The device is shut down and ready to be switched off.
//! After the command to set the switch off has been sent,
//! the mode changes to @c _MODE_WAIT_OFF
static const Mode_t _MODE_POWER_DOWN = TRANSITION_MODE_BASE_ACTION_MASK | 1;
//! This is a transitional state which can not be commanded. The device
//! will be switched on in this state. After the command to set the switch
//! on has been sent, the mode changes to @c _MODE_WAIT_ON.
static const Mode_t _MODE_POWER_ON = TRANSITION_MODE_BASE_ACTION_MASK | 2;
//! This is a transitional state which can not be commanded. The switch has
//! been commanded off and the handler waits for it to be off.
//! When the switch is off, the mode changes to @c MODE_OFF.
static const Mode_t _MODE_WAIT_OFF = TRANSITION_MODE_BASE_ACTION_MASK | 3;
//! This is a transitional state which can not be commanded. The switch
//! has been commanded on and the handler waits for it to be on.
//! When the switch is on, the mode changes to @c _MODE_TO_ON.
static const Mode_t _MODE_WAIT_ON = TRANSITION_MODE_BASE_ACTION_MASK | 4;
void setHkDestination(object_id_t hkDestination); void setHkDestination(object_id_t hkDestination);
/** /**
@ -110,13 +159,12 @@ class DeviceHandlerBase : public DeviceHandlerIF,
* The device handler will then take care of creating local pool entries * The device handler will then take care of creating local pool entries
* for the device thermal state and device heating request. * for the device thermal state and device heating request.
* Custom local pool IDs can be assigned as well. * Custom local pool IDs can be assigned as well.
* @param thermalStatePoolId
* @param thermalRequestPoolId
*/ */
void setThermalStateRequestPoolIds( void enableThermalModule(ThermalStateCfg cfg);
lp_id_t thermalStatePoolId = DeviceHandlerIF::DEFAULT_THERMAL_STATE_POOL_ID,
lp_id_t thermalRequestPoolId = DeviceHandlerIF::DEFAULT_THERMAL_HEATING_REQUEST_POOL_ID, ReturnValue_t connectModeTreeParent(HasModeTreeChildrenIF &parent) override;
uint32_t thermalSetId = DeviceHandlerIF::DEFAULT_THERMAL_SET_ID); ModeTreeChildIF &getModeTreeChildIF() override;
/** /**
* @brief Helper function to ease device handler development. * @brief Helper function to ease device handler development.
* This will instruct the transition to MODE_ON immediately * This will instruct the transition to MODE_ON immediately
@ -162,7 +210,7 @@ class DeviceHandlerBase : public DeviceHandlerIF,
* @param counter Specifies which Action to perform * @param counter Specifies which Action to perform
* @return returnvalue::OK for successful execution * @return returnvalue::OK for successful execution
*/ */
virtual ReturnValue_t performOperation(uint8_t counter) override; ReturnValue_t performOperation(uint8_t counter) override;
/** /**
* @brief Initializes the device handler * @brief Initializes the device handler
@ -172,14 +220,14 @@ class DeviceHandlerBase : public DeviceHandlerIF,
* Calls fillCommandAndReplyMap(). * Calls fillCommandAndReplyMap().
* @return * @return
*/ */
virtual ReturnValue_t initialize() override; ReturnValue_t initialize() override;
/** /**
* @brief Intialization steps performed after all tasks have been created. * @brief Intialization steps performed after all tasks have been created.
* This function will be called by the executing task. * This function will be called by the executing task.
* @return * @return
*/ */
virtual ReturnValue_t initializeAfterTaskCreation() override; ReturnValue_t initializeAfterTaskCreation() override;
/** Destructor. */ /** Destructor. */
virtual ~DeviceHandlerBase(); virtual ~DeviceHandlerBase();
@ -196,6 +244,8 @@ class DeviceHandlerBase : public DeviceHandlerIF,
virtual object_id_t getObjectId() const override; virtual object_id_t getObjectId() const override;
/** /**
* This is a helper method for classes which are parent nodes in the mode tree.
* It registers the passed queue as the destination for mode and health messages.
* @param parentQueueId * @param parentQueueId
*/ */
virtual void setParentQueue(MessageQueueId_t parentQueueId); virtual void setParentQueue(MessageQueueId_t parentQueueId);
@ -207,8 +257,8 @@ class DeviceHandlerBase : public DeviceHandlerIF,
Mode_t getTransitionSourceMode() const; Mode_t getTransitionSourceMode() const;
Submode_t getTransitionSourceSubMode() const; Submode_t getTransitionSourceSubMode() const;
virtual void getMode(Mode_t *mode, Submode_t *submode); virtual void getMode(Mode_t *mode, Submode_t *submode);
HealthState getHealth(); virtual HealthState getHealth() override;
ReturnValue_t setHealth(HealthState health); virtual ReturnValue_t setHealth(HealthState health) override;
virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId, virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueId,
ParameterWrapper *parameterWrapper, ParameterWrapper *parameterWrapper,
const ParameterWrapper *newValues, const ParameterWrapper *newValues,
@ -395,6 +445,8 @@ class DeviceHandlerBase : public DeviceHandlerIF,
*/ */
virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) = 0; virtual ReturnValue_t interpretDeviceReply(DeviceCommandId_t id, const uint8_t *packet) = 0;
MessageQueueId_t getCommanderQueueId(DeviceCommandId_t replyId) const; MessageQueueId_t getCommanderQueueId(DeviceCommandId_t replyId) const;
ReturnValue_t finishAction(bool success, DeviceCommandId_t action, ReturnValue_t result);
/** /**
* Helper function to get pending command. This is useful for devices * Helper function to get pending command. This is useful for devices
* like SPI sensors to identify the last sent command. * like SPI sensors to identify the last sent command.
@ -463,14 +515,14 @@ class DeviceHandlerBase : public DeviceHandlerIF,
* @brief This is a helper method to insert replies in the reply map. * @brief This is a helper method to insert replies in the reply map.
* @param deviceCommand Identifier of the reply to add. * @param deviceCommand Identifier of the reply to add.
* @param maxDelayCycles The maximum number of delay cycles the reply waits * @param maxDelayCycles The maximum number of delay cycles the reply waits
* until it times out. * until it times out.
* @param periodic Indicates if the command is periodic (i.e. it is sent * @param periodic Indicates if the command is periodic (i.e. it is sent
* by the device repeatedly without request) or not. Default is aperiodic (0). * by the device repeatedly without request) or not. Default is aperiodic (0).
* Please note that periodic replies are disabled by default. You can enable them with * Please note that periodic replies are disabled by default. You can enable them with
* #updatePeriodicReply * #updatePeriodicReply
* @param countdown Instead of using maxDelayCycles to timeout a device reply it is also possible * @param countdown Instead of using maxDelayCycles to timeout a device reply it is also possible
* to provide a pointer to a Countdown object which will signal the timeout * to provide a pointer to a Countdown object which will signal the timeout
* when expired * when expired
* @return - @c returnvalue::OK when the command was successfully inserted, * @return - @c returnvalue::OK when the command was successfully inserted,
* - @c returnvalue::FAILED else. * - @c returnvalue::FAILED else.
*/ */
@ -655,6 +707,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;
@ -684,15 +742,18 @@ class DeviceHandlerBase : public DeviceHandlerIF,
size_t rawPacketLen = 0; size_t rawPacketLen = 0;
/** /**
* The mode the device handler is currently in. * Get the current mode
* This should never be changed directly but only with setMode() *
* set via setMode()
*/ */
Mode_t mode; Mode_t getMode();
/** /**
* The submode the device handler is currently in. * Get the current Submode
* This should never be changed directly but only with setMode() *
* set via setMode()
*/ */
Submode_t submode; Submode_t getSubmode();
/** This is the counter value from performOperation(). */ /** This is the counter value from performOperation(). */
uint8_t pstStep = 0; uint8_t pstStep = 0;
@ -773,11 +834,18 @@ class DeviceHandlerBase : public DeviceHandlerIF,
* This is used to keep track of pending replies. * This is used to keep track of pending replies.
*/ */
struct DeviceReplyInfo { struct DeviceReplyInfo {
//! For Command-Reply combinations:
//! The maximum number of cycles the handler should wait for a reply //! The maximum number of cycles the handler should wait for a reply
//! to this command. //! to this command.
//!
//! Reply Only:
//! For periodic replies, this variable will be the number of delay cycles between the replies.
//! For the non-periodic variant, this variable is not used as there is no meaningful
//! definition for delay
uint16_t maxDelayCycles; uint16_t maxDelayCycles;
//! The currently remaining cycles the handler should wait for a reply, //! This variable will be set to #maxDelayCycles if a reply is expected.
//! 0 means there is no reply expected //! For non-periodic replies without a command, this variable is unused.
//! A runtime value of 0 means there is no reply is currently expected.
uint16_t delayCycles; uint16_t delayCycles;
size_t replyLen = 0; //!< Expected size of the reply. size_t replyLen = 0; //!< Expected size of the reply.
//! if this is !=0, the delayCycles will not be reset to 0 but to //! if this is !=0, the delayCycles will not be reset to 0 but to
@ -833,6 +901,7 @@ class DeviceHandlerBase : public DeviceHandlerIF,
/** Pointer to the used FDIR instance. If not provided by child, /** Pointer to the used FDIR instance. If not provided by child,
* default class is instantiated. */ * default class is instantiated. */
FailureIsolationBase *fdirInstance; FailureIsolationBase *fdirInstance;
object_id_t parent = objects::NO_OBJECT;
//! To correctly delete the default instance. //! To correctly delete the default instance.
bool defaultFDIRUsed; bool defaultFDIRUsed;
@ -853,6 +922,8 @@ class DeviceHandlerBase : public DeviceHandlerIF,
//! Object which may be the root cause of an identified fault. //! Object which may be the root cause of an identified fault.
static object_id_t defaultFdirParentId; static object_id_t defaultFdirParentId;
std::optional<ThermalStateCfg> thermalStateCfg;
/** /**
* @brief Send a reply to a received device handler command. * @brief Send a reply to a received device handler command.
* *
@ -873,8 +944,8 @@ class DeviceHandlerBase : public DeviceHandlerIF,
* Do the transition to the main modes (MODE_ON, MODE_NORMAL and MODE_RAW). * Do the transition to the main modes (MODE_ON, MODE_NORMAL and MODE_RAW).
* *
* If the transition is complete, the mode should be set to the target mode, * If the transition is complete, the mode should be set to the target mode,
* which can be deduced from the current mode which is * which can be deduced from the current mode (which is
* [_MODE_TO_ON, _MODE_TO_NORMAL, _MODE_TO_RAW] * [_MODE_TO_ON, _MODE_TO_NORMAL, _MODE_TO_RAW]) using getBaseMode()
* *
* The intended target submode is already set. * The intended target submode is already set.
* The origin submode can be read in subModeFrom. * The origin submode can be read in subModeFrom.
@ -941,6 +1012,9 @@ class DeviceHandlerBase : public DeviceHandlerIF,
*/ */
LocalDataPoolManager *getHkManagerHandle() override; LocalDataPoolManager *getHkManagerHandle() override;
const HasHealthIF *getOptHealthIF() const override;
const HasModesIF &getModeIF() const override;
/** /**
* Returns the delay cycle count of a reply. * Returns the delay cycle count of a reply.
* A count != 0 indicates that the command is already executed. * A count != 0 indicates that the command is already executed.
@ -1120,6 +1194,22 @@ class DeviceHandlerBase : public DeviceHandlerIF,
*/ */
virtual ReturnValue_t doSendReadHook(); virtual ReturnValue_t doSendReadHook();
/**
* Send a RMAP getRead command.
*
* The size of the getRead command is #maxDeviceReplyLen.
* This is always executed, independently from the current mode.
*/
virtual void doSendRead(void);
/**
* Check the getRead reply and the contained data.
*
* If data was received scanForReply() and, if successful, handleReply()
* are called. If the current mode is @c MODE_RAW, the received packet
* is sent to the commanding object via commandQueue.
*/
virtual void doGetRead();
private: private:
/** /**
* State a cookie is in. * State a cookie is in.
@ -1170,6 +1260,18 @@ class DeviceHandlerBase : public DeviceHandlerIF,
*/ */
uint32_t childTransitionDelay; uint32_t childTransitionDelay;
/**
* The mode the device handler is currently in.
* This should not be changed directly but only with setMode()
*/
Mode_t mode;
/**
* The submode the device handler is currently in.
* This should not be changed directly but only with setMode()
*/
Submode_t submode;
/** /**
* @brief The mode the current transition originated from * @brief The mode the current transition originated from
* *
@ -1187,6 +1289,15 @@ class DeviceHandlerBase : public DeviceHandlerIF,
*/ */
Submode_t transitionSourceSubMode; Submode_t transitionSourceSubMode;
/**
* used to make the state machine continue from ON to NOMAL when
* a Device is commanded to NORMAL in OFF mode
*
* set in startTransition()
* evaluated in setMode() to continue to NORMAL when ON is reached
*/
bool continueToNormal;
/** /**
* read the command queue * read the command queue
*/ */
@ -1255,21 +1366,6 @@ class DeviceHandlerBase : public DeviceHandlerIF,
* - if the action was successful, the reply timout counter is initialized * - if the action was successful, the reply timout counter is initialized
*/ */
void doGetWrite(void); void doGetWrite(void);
/**
* Send a RMAP getRead command.
*
* The size of the getRead command is #maxDeviceReplyLen.
* This is always executed, independently from the current mode.
*/
void doSendRead(void);
/**
* Check the getRead reply and the contained data.
*
* If data was received scanForReply() and, if successful, handleReply()
* are called. If the current mode is @c MODE_RAW, the received packet
* is sent to the commanding object via commandQueue.
*/
void doGetRead(void);
/** /**
* @brief Resets replies which use a timeout to detect missed replies. * @brief Resets replies which use a timeout to detect missed replies.
@ -1323,6 +1419,11 @@ class DeviceHandlerBase : public DeviceHandlerIF,
void printWarningOrError(sif::OutputTypes errorType, const char *functionName, void printWarningOrError(sif::OutputTypes errorType, const char *functionName,
ReturnValue_t errorCode = returnvalue::FAILED, ReturnValue_t errorCode = returnvalue::FAILED,
const char *errorPrint = nullptr); const char *errorPrint = nullptr);
/**
* @brief Disables all commands and replies when device is set to MODE_OFF
*/
void disableCommandsAndReplies();
}; };
#endif /* FSFW_DEVICEHANDLERS_DEVICEHANDLERBASE_H_ */ #endif /* FSFW_DEVICEHANDLERS_DEVICEHANDLERBASE_H_ */

View File

@ -10,8 +10,9 @@
object_id_t DeviceHandlerFailureIsolation::powerConfirmationId = objects::NO_OBJECT; object_id_t DeviceHandlerFailureIsolation::powerConfirmationId = objects::NO_OBJECT;
DeviceHandlerFailureIsolation::DeviceHandlerFailureIsolation(object_id_t owner, object_id_t parent) DeviceHandlerFailureIsolation::DeviceHandlerFailureIsolation(object_id_t owner, object_id_t parent,
: FailureIsolationBase(owner, parent), uint8_t eventQueueDepth)
: FailureIsolationBase(owner, parent, eventQueueDepth),
strangeReplyCount(DEFAULT_MAX_STRANGE_REPLIES, DEFAULT_STRANGE_REPLIES_TIME_MS, strangeReplyCount(DEFAULT_MAX_STRANGE_REPLIES, DEFAULT_STRANGE_REPLIES_TIME_MS,
parameterDomainBase++), parameterDomainBase++),
missedReplyCount(DEFAULT_MAX_MISSED_REPLY_COUNT, DEFAULT_MISSED_REPLY_TIME_MS, missedReplyCount(DEFAULT_MAX_MISSED_REPLY_COUNT, DEFAULT_MISSED_REPLY_TIME_MS,
@ -29,6 +30,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

@ -13,7 +13,8 @@ class DeviceHandlerFailureIsolation : public FailureIsolationBase {
friend class Heater; friend class Heater;
public: public:
DeviceHandlerFailureIsolation(object_id_t owner, object_id_t parent); DeviceHandlerFailureIsolation(object_id_t owner, object_id_t parent,
uint8_t eventQueueDepth = 10);
~DeviceHandlerFailureIsolation(); ~DeviceHandlerFailureIsolation();
ReturnValue_t initialize(); ReturnValue_t initialize();
void triggerEvent(Event event, uint32_t parameter1 = 0, uint32_t parameter2 = 0); void triggerEvent(Event event, uint32_t parameter1 = 0, uint32_t parameter2 = 0);

View File

@ -24,9 +24,6 @@ class DeviceHandlerIF {
static const DeviceCommandId_t RAW_COMMAND_ID = -1; static const DeviceCommandId_t RAW_COMMAND_ID = -1;
static const DeviceCommandId_t NO_COMMAND_ID = -2; static const DeviceCommandId_t NO_COMMAND_ID = -2;
static constexpr uint8_t TRANSITION_MODE_CHILD_ACTION_MASK = 0x20;
static constexpr uint8_t TRANSITION_MODE_BASE_ACTION_MASK = 0x10;
using dh_heater_request_t = uint8_t; using dh_heater_request_t = uint8_t;
using dh_thermal_state_t = int8_t; using dh_thermal_state_t = int8_t;
@ -54,47 +51,6 @@ class DeviceHandlerIF {
//! device still is powered. In this mode, only a mode change to @c MODE_OFF //! device still is powered. In this mode, only a mode change to @c MODE_OFF
//! can be commanded, which tries to switch off the device again. //! can be commanded, which tries to switch off the device again.
static const Mode_t MODE_ERROR_ON = 4; static const Mode_t MODE_ERROR_ON = 4;
//! This is a transitional state which can not be commanded. The device
//! handler performs all commands to get the device in a state ready to
//! perform commands. When this is completed, the mode changes to @c MODE_ON.
static const Mode_t _MODE_START_UP = TRANSITION_MODE_CHILD_ACTION_MASK | 5;
//! This is a transitional state which can not be commanded.
//! The device handler performs all actions and commands to get the device
//! shut down. When the device is off, the mode changes to @c MODE_OFF.
//! It is possible to set the mode to _MODE_SHUT_DOWN to use the to off
//! transition if available.
static const Mode_t _MODE_SHUT_DOWN = TRANSITION_MODE_CHILD_ACTION_MASK | 6;
//! It is possible to set the mode to _MODE_TO_ON to use the to on
//! transition if available.
static const Mode_t _MODE_TO_ON = TRANSITION_MODE_CHILD_ACTION_MASK | HasModesIF::MODE_ON;
//! It is possible to set the mode to _MODE_TO_RAW to use the to raw
//! transition if available.
static const Mode_t _MODE_TO_RAW = TRANSITION_MODE_CHILD_ACTION_MASK | MODE_RAW;
//! It is possible to set the mode to _MODE_TO_NORMAL to use the to normal
//! transition if available.
static const Mode_t _MODE_TO_NORMAL = TRANSITION_MODE_CHILD_ACTION_MASK | MODE_NORMAL;
//! This is a transitional state which can not be commanded.
//! The device is shut down and ready to be switched off.
//! After the command to set the switch off has been sent,
//! the mode changes to @c MODE_WAIT_OFF
static const Mode_t _MODE_POWER_DOWN = TRANSITION_MODE_BASE_ACTION_MASK | 1;
//! This is a transitional state which can not be commanded. The device
//! will be switched on in this state. After the command to set the switch
//! on has been sent, the mode changes to @c MODE_WAIT_ON.
static const Mode_t _MODE_POWER_ON = TRANSITION_MODE_BASE_ACTION_MASK | 2;
//! This is a transitional state which can not be commanded. The switch has
//! been commanded off and the handler waits for it to be off.
//! When the switch is off, the mode changes to @c MODE_OFF.
static const Mode_t _MODE_WAIT_OFF = TRANSITION_MODE_BASE_ACTION_MASK | 3;
//! This is a transitional state which can not be commanded. The switch
//! has been commanded on and the handler waits for it to be on.
//! When the switch is on, the mode changes to @c MODE_TO_ON.
static const Mode_t _MODE_WAIT_ON = TRANSITION_MODE_BASE_ACTION_MASK | 4;
//! This is a transitional state which can not be commanded. The switch has
//! been commanded off and is off now. This state is only to do an RMAP
//! cycle once more where the doSendRead() function will set the mode to
//! MODE_OFF. The reason to do this is to get rid of stuck packets in the IO Board.
static const Mode_t _MODE_SWITCH_IS_OFF = TRANSITION_MODE_BASE_ACTION_MASK | 5;
static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::CDH; static const uint8_t SUBSYSTEM_ID = SUBSYSTEM_ID::CDH;
static const Event DEVICE_BUILDING_COMMAND_FAILED = MAKE_EVENT(0, severity::LOW); static const Event DEVICE_BUILDING_COMMAND_FAILED = MAKE_EVENT(0, severity::LOW);
@ -109,6 +65,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;
@ -179,4 +136,10 @@ class DeviceHandlerIF {
virtual MessageQueueId_t getCommandQueue() const = 0; virtual MessageQueueId_t getCommandQueue() const = 0;
}; };
struct ThermalStateCfg {
lp_id_t thermalStatePoolId = DeviceHandlerIF::DEFAULT_THERMAL_STATE_POOL_ID;
lp_id_t thermalRequestPoolId = DeviceHandlerIF::DEFAULT_THERMAL_HEATING_REQUEST_POOL_ID;
uint32_t thermalSetId = DeviceHandlerIF::DEFAULT_THERMAL_SET_ID;
};
#endif /* FSFW_DEVICEHANDLERS_DEVICEHANDLERIF_H_ */ #endif /* FSFW_DEVICEHANDLERS_DEVICEHANDLERIF_H_ */

View File

@ -7,27 +7,21 @@
class DeviceHandlerThermalSet : public StaticLocalDataSet<2> { class DeviceHandlerThermalSet : public StaticLocalDataSet<2> {
public: public:
DeviceHandlerThermalSet( DeviceHandlerThermalSet(HasLocalDataPoolIF* hkOwner, ThermalStateCfg cfg)
HasLocalDataPoolIF* hkOwner, uint32_t setId = DeviceHandlerIF::DEFAULT_THERMAL_SET_ID, : DeviceHandlerThermalSet(hkOwner->getObjectId(), cfg) {}
lp_id_t thermalStateId = DeviceHandlerIF::DEFAULT_THERMAL_STATE_POOL_ID,
lp_id_t heaterRequestId = DeviceHandlerIF::DEFAULT_THERMAL_HEATING_REQUEST_POOL_ID)
: DeviceHandlerThermalSet(hkOwner->getObjectId(), setId, thermalStateId, heaterRequestId) {}
DeviceHandlerThermalSet( DeviceHandlerThermalSet(object_id_t deviceHandler, ThermalStateCfg cfg)
object_id_t deviceHandler, uint32_t setId = DeviceHandlerIF::DEFAULT_THERMAL_SET_ID, : StaticLocalDataSet(sid_t(deviceHandler, cfg.thermalSetId)),
lp_id_t thermalStateId = DeviceHandlerIF::DEFAULT_THERMAL_STATE_POOL_ID, thermalStatePoolId(cfg.thermalStatePoolId),
lp_id_t thermalStateRequestId = DeviceHandlerIF::DEFAULT_THERMAL_HEATING_REQUEST_POOL_ID) heaterRequestPoolId(cfg.thermalRequestPoolId) {}
: StaticLocalDataSet(sid_t(deviceHandler, setId)),
thermalStatePoolId(thermalStateId),
heaterRequestPoolId(thermalStateRequestId) {}
const lp_id_t thermalStatePoolId; const lp_id_t thermalStatePoolId;
const lp_id_t heaterRequestPoolId; const lp_id_t heaterRequestPoolId;
lp_var_t<DeviceHandlerIF::dh_thermal_state_t> thermalState = lp_var_t<DeviceHandlerIF::dh_thermal_state_t> thermalState =
lp_var_t<DeviceHandlerIF::dh_thermal_state_t>(thermalStatePoolId, sid.objectId, this); lp_var_t<DeviceHandlerIF::dh_thermal_state_t>(sid.objectId, thermalStatePoolId, this);
lp_var_t<DeviceHandlerIF::dh_heater_request_t> heaterRequest = lp_var_t<DeviceHandlerIF::dh_heater_request_t> heaterRequest =
lp_var_t<DeviceHandlerIF::dh_heater_request_t>(heaterRequestPoolId, sid.objectId, this); lp_var_t<DeviceHandlerIF::dh_heater_request_t>(sid.objectId, heaterRequestPoolId, this);
}; };
#endif /* FSFW_DEVICEHANDLERS_DEVICEHANDLERTHERMALSET_H_ */ #endif /* FSFW_DEVICEHANDLERS_DEVICEHANDLERTHERMALSET_H_ */

View File

@ -1,9 +1,9 @@
#ifndef FSFW_DEVICEHANDLERS_DEVICETMREPORTINGWRAPPER_H_ #ifndef FSFW_DEVICEHANDLERS_DEVICETMREPORTINGWRAPPER_H_
#define FSFW_DEVICEHANDLERS_DEVICETMREPORTINGWRAPPER_H_ #define FSFW_DEVICEHANDLERS_DEVICETMREPORTINGWRAPPER_H_
#include "../action/HasActionsIF.h" #include "fsfw/action/HasActionsIF.h"
#include "../objectmanager/SystemObjectIF.h" #include "fsfw/objectmanager/SystemObjectIF.h"
#include "../serialize/SerializeIF.h" #include "fsfw/serialize/SerializeIF.h"
class DeviceTmReportingWrapper : public SerializeIF { class DeviceTmReportingWrapper : public SerializeIF {
public: public:

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); }
@ -27,11 +29,10 @@ ReturnValue_t HealthDevice::initialize() {
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
return result; return result;
} }
if (parentQueue != 0) { if (parentQueue != MessageQueueIF::NO_QUEUE) {
return healthHelper.initialize(parentQueue); return healthHelper.initialize(parentQueue);
} else {
return healthHelper.initialize();
} }
return healthHelper.initialize();
} }
MessageQueueId_t HealthDevice::getCommandQueue() const { return commandQueue->getId(); } MessageQueueId_t HealthDevice::getCommandQueue() const { return commandQueue->getId(); }

View File

@ -29,10 +29,8 @@ class HealthDevice : public SystemObject, public ExecutableObjectIF, public HasH
protected: protected:
HealthState lastHealth; HealthState lastHealth;
MessageQueueId_t parentQueue; MessageQueueId_t parentQueue = MessageQueueIF::NO_QUEUE;
MessageQueueIF* commandQueue; MessageQueueIF* commandQueue;
public:
HealthHelper healthHelper; HealthHelper healthHelper;
}; };

View File

@ -15,11 +15,12 @@ const LocalPool::LocalPoolConfig EventManager::poolConfig = {
{fsfwconfig::FSFW_EVENTMGMT_EVENTIDMATCHERS, sizeof(EventIdRangeMatcher)}, {fsfwconfig::FSFW_EVENTMGMT_EVENTIDMATCHERS, sizeof(EventIdRangeMatcher)},
{fsfwconfig::FSFW_EVENTMGMR_RANGEMATCHERS, sizeof(ReporterRangeMatcher)}}; {fsfwconfig::FSFW_EVENTMGMR_RANGEMATCHERS, sizeof(ReporterRangeMatcher)}};
EventManager::EventManager(object_id_t setObjectId) EventManager::EventManager(object_id_t setObjectId, uint32_t eventQueueDepth)
: 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(
eventQueueDepth, EventMessage::EVENT_MESSAGE_SIZE, &mqArgs);
} }
EventManager::~EventManager() { EventManager::~EventManager() {
@ -47,9 +48,21 @@ 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 != returnvalue::OK) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::error << std::hex << "EventManager::notifyListeners: MSG to 0x" << std::setfill('0')
<< std::setw(8) << listener.first << " for event 0x" << std::setw(4)
<< message->getEventId() << " 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();
@ -200,4 +213,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

@ -21,9 +21,9 @@ extern const char* translateEvents(Event event);
class EventManager : public EventManagerIF, public ExecutableObjectIF, public SystemObject { class EventManager : public EventManagerIF, public ExecutableObjectIF, public SystemObject {
public: public:
static const uint16_t MAX_EVENTS_PER_CYCLE = 80; static const uint16_t DEFAULT_MAX_EVENTS_PER_CYCLE = 80;
EventManager(object_id_t setObjectId); EventManager(object_id_t setObjectId, uint32_t eventQueueDepth);
virtual ~EventManager(); virtual ~EventManager();
void setMutexTimeout(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs); void setMutexTimeout(MutexIF::TimeoutType timeoutType, uint32_t timeoutMs);
@ -44,6 +44,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() {
@ -61,11 +62,12 @@ ReturnValue_t FailureIsolationBase::initialize() {
ObjectManager::instance()->get<ConfirmsFailuresIF>(faultTreeParent); ObjectManager::instance()->get<ConfirmsFailuresIF>(faultTreeParent);
if (parentIF == nullptr) { if (parentIF == nullptr) {
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::error << "FailureIsolationBase::intialize: Parent object" sif::error << "FailureIsolationBase::intialize: Parent object "
<< "invalid." << std::endl; << "invalid" << std::endl;
#endif sif::error << "Make sure it implements ConfirmsFailuresIF" << std::endl;
#if FSFW_CPP_OSTREAM_ENABLED == 1 #else
sif::error << "Make sure it implements ConfirmsFailuresIF." << std::endl; sif::printError("FailureIsolationBase::intialize: Parent object invalid\n");
sif::printError("Make sure it implements ConfirmsFailuresIF\n");
#endif #endif
return ObjectManagerIF::CHILD_INIT_FAILED; return ObjectManagerIF::CHILD_INIT_FAILED;
return returnvalue::FAILED; return returnvalue::FAILED;

View File

@ -12,13 +12,12 @@
class FailureIsolationBase : public ConfirmsFailuresIF, public HasParametersIF { class FailureIsolationBase : public ConfirmsFailuresIF, 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

@ -68,7 +68,7 @@ ReturnValue_t FaultCounter::getParameter(uint8_t domainId, uint8_t uniqueId,
parameterWrapper->set(faultCount); parameterWrapper->set(faultCount);
break; break;
case ParameterIds::TIMEOUT: case ParameterIds::TIMEOUT:
parameterWrapper->set(timer.timeout); parameterWrapper->set(timer.getTimeoutMs());
break; break;
default: default:
return INVALID_IDENTIFIER_ID; return INVALID_IDENTIFIER_ID;

View File

@ -40,6 +40,7 @@ class HasFileSystemIF {
//! [EXPORT] : P1: Can be file system specific error code //! [EXPORT] : P1: Can be file system specific error code
static constexpr ReturnValue_t GENERIC_FILE_ERROR = MAKE_RETURN_CODE(0); static constexpr ReturnValue_t GENERIC_FILE_ERROR = MAKE_RETURN_CODE(0);
static constexpr ReturnValue_t GENERIC_DIR_ERROR = MAKE_RETURN_CODE(1); static constexpr ReturnValue_t GENERIC_DIR_ERROR = MAKE_RETURN_CODE(1);
static constexpr ReturnValue_t FILESYSTEM_INACTIVE = MAKE_RETURN_CODE(2);
static constexpr ReturnValue_t GENERIC_RENAME_ERROR = MAKE_RETURN_CODE(3); static constexpr ReturnValue_t GENERIC_RENAME_ERROR = MAKE_RETURN_CODE(3);
//! [EXPORT] : File system is currently busy //! [EXPORT] : File system is currently busy
@ -73,6 +74,12 @@ class HasFileSystemIF {
return MessageQueueIF::NO_QUEUE; return MessageQueueIF::NO_QUEUE;
} }
// Get the base filename without the full directory path
virtual ReturnValue_t getBaseFilename(FilesystemParams params, char* nameBuf, size_t maxLen,
size_t& baseNameLen) = 0;
virtual bool isDirectory(const char* path) = 0;
virtual bool fileExists(FilesystemParams params) = 0; virtual bool fileExists(FilesystemParams params) = 0;
/** /**

View File

@ -63,9 +63,8 @@ ReturnValue_t DleParser::parseRingBuf(size_t& readSize) {
size_t decodedLen = 0; size_t decodedLen = 0;
size_t dummy = 0; size_t dummy = 0;
result = result = decoder.decode(&encodedBuf.first[stxIdx], availableData - stxIdx, &dummy,
decoder.decode(&encodedBuf.first[stxIdx], availableData - stxIdx, &dummy, decodedBuf.first, decodedBuf.second, &decodedLen);
decodedBuf.first, decodedBuf.second, &decodedLen);
if (result == returnvalue::OK) { if (result == returnvalue::OK) {
ctx.setType(ContextType::PACKET_FOUND); ctx.setType(ContextType::PACKET_FOUND);
ctx.decodedPacket.first = decodedBuf.first; ctx.decodedPacket.first = decodedBuf.first;

View File

@ -18,8 +18,11 @@
*/ */
class DleParser { class DleParser {
public: public:
//! [EXPORT] : [SKIP]
static constexpr ReturnValue_t NO_PACKET_FOUND = returnvalue::makeCode(1, 1); static constexpr ReturnValue_t NO_PACKET_FOUND = returnvalue::makeCode(1, 1);
//! [EXPORT] : [SKIP]
static constexpr ReturnValue_t POSSIBLE_PACKET_LOSS = returnvalue::makeCode(1, 2); static constexpr ReturnValue_t POSSIBLE_PACKET_LOSS = returnvalue::makeCode(1, 2);
using BufPair = std::pair<uint8_t*, size_t>; using BufPair = std::pair<uint8_t*, size_t>;
enum class ContextType { NONE, PACKET_FOUND, ERROR }; enum class ContextType { NONE, PACKET_FOUND, ERROR };

View File

@ -53,8 +53,9 @@ class VectorOperations {
mulScalar(vector, 1 / norm(vector, size), normalizedVector, size); mulScalar(vector, 1 / norm(vector, size), normalizedVector, size);
} }
static T maxAbsValue(const T *vector, uint8_t size, uint8_t *index = 0) { static T maxAbsValue(const T *vector, uint8_t size, uint8_t *index = nullptr) {
T max = -1; T max = vector[size - 1];
uint8_t foundIndex = size - 1;
for (; size > 0; size--) { for (; size > 0; size--) {
T abs = vector[size - 1]; T abs = vector[size - 1];
@ -64,24 +65,35 @@ class VectorOperations {
if (abs > max) { if (abs > max) {
max = abs; max = abs;
if (index != 0) { if (index != 0) {
*index = size - 1; foundIndex = size - 1;
} }
} }
} }
if (index != nullptr) {
*index = foundIndex;
}
return max; return max;
} }
static T maxValue(const T *vector, uint8_t size, uint8_t *index = 0) { static T maxValue(const T *vector, uint8_t size, uint8_t *index = nullptr) {
T max = -1; T max = vector[size - 1];
uint8_t foundIndex = size - 1;
for (; size > 0; size--) { for (; size > 0; size--) {
if (vector[size - 1] > max) { if (vector[size - 1] > max) {
max = vector[size - 1]; max = vector[size - 1];
if (index != 0) { if (index != 0) {
*index = size - 1; foundIndex = size - 1;
} }
} }
} }
if (index != nullptr) {
*index = foundIndex;
}
return max; return max;
} }

View File

@ -8,10 +8,8 @@ PeriodicHousekeepingHelper::PeriodicHousekeepingHelper(LocalPoolDataSetBase* own
: owner(owner) {} : owner(owner) {}
void PeriodicHousekeepingHelper::initialize(float collectionInterval, void PeriodicHousekeepingHelper::initialize(float collectionInterval,
dur_millis_t minimumPeriodicInterval, dur_millis_t minimumPeriodicInterval) {
uint8_t nonDiagIntervalFactor) {
this->minimumPeriodicInterval = minimumPeriodicInterval; this->minimumPeriodicInterval = minimumPeriodicInterval;
this->nonDiagIntervalFactor = nonDiagIntervalFactor;
collectionIntervalTicks = intervalSecondsToIntervalTicks(collectionInterval); collectionIntervalTicks = intervalSecondsToIntervalTicks(collectionInterval);
/* This will cause a checkOpNecessary call to be true immediately. I think it's okay /* This will cause a checkOpNecessary call to be true immediately. I think it's okay
if a HK packet is generated immediately instead of waiting one generation cycle. */ if a HK packet is generated immediately instead of waiting one generation cycle. */
@ -36,42 +34,17 @@ uint32_t PeriodicHousekeepingHelper::intervalSecondsToIntervalTicks(
if (owner == nullptr) { if (owner == nullptr) {
return 0; return 0;
} }
bool isDiagnostics = owner->isDiagnostics();
/* Avoid division by zero */ /* Avoid division by zero */
if (minimumPeriodicInterval == 0) { if (minimumPeriodicInterval == 0) {
if (isDiagnostics) { /* Perform operation each cycle */
/* Perform operation each cycle */ return 1;
return 1;
} else {
return nonDiagIntervalFactor;
}
} else { } else {
dur_millis_t intervalInMs = collectionIntervalSeconds * 1000; dur_millis_t intervalInMs = collectionIntervalSeconds * 1000;
uint32_t divisor = minimumPeriodicInterval; uint32_t divisor = minimumPeriodicInterval;
if (not isDiagnostics) {
/* We need to multiply the divisor because non-diagnostics only
allow a multiple of the minimum periodic interval */
divisor *= nonDiagIntervalFactor;
}
uint32_t ticks = std::ceil(static_cast<float>(intervalInMs) / divisor); uint32_t ticks = std::ceil(static_cast<float>(intervalInMs) / divisor);
if (not isDiagnostics) {
/* Now we need to multiply the calculated ticks with the factor as as well
because the minimum tick count to generate a non-diagnostic is the factor itself.
Example calculation for non-diagnostic with
0.4 second interval and 0.2 second task interval.
Resultant tick count of 5 is equal to operation each second.
Examle calculation for non-diagnostic with 2.0 second interval and 0.2 second
task interval.
Resultant tick count of 10 is equal to operatin every 2 seconds.
Example calculation for diagnostic with 0.4 second interval and 0.3
second task interval. Resulting tick count of 2 is equal to operation
every 0.6 seconds. */
ticks *= nonDiagIntervalFactor;
}
return ticks; return ticks;
} }
} }

View File

@ -11,8 +11,7 @@ class PeriodicHousekeepingHelper {
public: public:
PeriodicHousekeepingHelper(LocalPoolDataSetBase* owner); PeriodicHousekeepingHelper(LocalPoolDataSetBase* owner);
void initialize(float collectionInterval, dur_millis_t minimumPeriodicInterval, void initialize(float collectionInterval, dur_millis_t minimumPeriodicInterval);
uint8_t nonDiagIntervalFactor);
void changeCollectionInterval(float newInterval); void changeCollectionInterval(float newInterval);
float getCollectionIntervalInSeconds() const; float getCollectionIntervalInSeconds() const;
@ -20,7 +19,6 @@ class PeriodicHousekeepingHelper {
private: private:
LocalPoolDataSetBase* owner = nullptr; LocalPoolDataSetBase* owner = nullptr;
uint8_t nonDiagIntervalFactor = 0;
uint32_t intervalSecondsToIntervalTicks(float collectionIntervalSeconds); uint32_t intervalSecondsToIntervalTicks(float collectionIntervalSeconds);
float intervalTicksToSeconds(uint32_t collectionInterval) const; float intervalTicksToSeconds(uint32_t collectionInterval) const;

View File

@ -5,13 +5,19 @@
#include "fsfw/ipc/QueueFactory.h" #include "fsfw/ipc/QueueFactory.h"
#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/serviceinterface/ServiceInterface.h"
InternalErrorReporter::InternalErrorReporter(object_id_t setObjectId, uint32_t messageQueueDepth) InternalErrorReporter::InternalErrorReporter(object_id_t setObjectId, uint32_t messageQueueDepth,
bool enableSetByDefault, float generationFrequency)
: SystemObject(setObjectId), : SystemObject(setObjectId),
poolManager(this, commandQueue), poolManager(this, commandQueue),
enableSetByDefault(enableSetByDefault),
generationFrequency(generationFrequency),
internalErrorSid(setObjectId, InternalErrorDataset::ERROR_SET_ID), internalErrorSid(setObjectId, InternalErrorDataset::ERROR_SET_ID),
internalErrorDataset(this) { internalErrorDataset(this) {
commandQueue = QueueFactory::instance()->createMessageQueue(messageQueueDepth); commandQueue = QueueFactory::instance()->createMessageQueue(messageQueueDepth);
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() { InternalErrorReporter::~InternalErrorReporter() {
@ -39,15 +45,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
} }
} }
@ -132,9 +137,8 @@ ReturnValue_t InternalErrorReporter::initializeLocalDataPool(localpool::DataPool
localDataPoolMap.emplace(errorPoolIds::TM_HITS, &tmHitsEntry); localDataPoolMap.emplace(errorPoolIds::TM_HITS, &tmHitsEntry);
localDataPoolMap.emplace(errorPoolIds::QUEUE_HITS, &queueHitsEntry); localDataPoolMap.emplace(errorPoolIds::QUEUE_HITS, &queueHitsEntry);
localDataPoolMap.emplace(errorPoolIds::STORE_HITS, &storeHitsEntry); localDataPoolMap.emplace(errorPoolIds::STORE_HITS, &storeHitsEntry);
poolManager.subscribeForDiagPeriodicPacket(subdp::DiagnosticsHkPeriodicParams( poolManager.subscribeForRegularPeriodicPacket(
internalErrorSid, false, subdp::RegularHkPeriodicParams(internalErrorSid, enableSetByDefault, generationFrequency));
static_cast<float>(getPeriodicOperationFrequency()) / static_cast<float>(1000.0)));
internalErrorDataset.setValidity(true, true); internalErrorDataset.setValidity(true, true);
return returnvalue::OK; return returnvalue::OK;
} }

View File

@ -21,7 +21,8 @@ class InternalErrorReporter : public SystemObject,
public InternalErrorReporterIF, public InternalErrorReporterIF,
public HasLocalDataPoolIF { public HasLocalDataPoolIF {
public: public:
InternalErrorReporter(object_id_t setObjectId, uint32_t messageQueueDepth = 5); InternalErrorReporter(object_id_t setObjectId, uint32_t messageQueueDepth,
bool enableSetByDefault, float generationFrequency);
/** /**
* Enable diagnostic printout. Please note that this feature will * Enable diagnostic printout. Please note that this feature will
@ -63,6 +64,8 @@ class InternalErrorReporter : public SystemObject,
MutexIF* mutex = nullptr; MutexIF* mutex = nullptr;
MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING; MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::WAITING;
uint32_t timeoutMs = 20; uint32_t timeoutMs = 20;
bool enableSetByDefault;
float generationFrequency;
sid_t internalErrorSid; sid_t internalErrorSid;
InternalErrorDataset internalErrorDataset; InternalErrorDataset internalErrorDataset;

View File

@ -34,7 +34,7 @@ class CommandMessageIF {
static const Command_t CMD_NONE = MAKE_COMMAND_ID(0); static const Command_t CMD_NONE = MAKE_COMMAND_ID(0);
static const Command_t REPLY_COMMAND_OK = MAKE_COMMAND_ID(1); static const Command_t REPLY_COMMAND_OK = MAKE_COMMAND_ID(1);
//! Reply indicating that the current command was rejected, //! Reply indicating that the current command was rejected,
//! par1 should contain the error code //! Parameter 1 should contain the error code
static const Command_t REPLY_REJECTED = MAKE_COMMAND_ID(2); static const Command_t REPLY_REJECTED = MAKE_COMMAND_ID(2);
virtual ~CommandMessageIF(){}; virtual ~CommandMessageIF(){};

View File

@ -7,14 +7,17 @@
class MutexGuard { class MutexGuard {
public: public:
MutexGuard(MutexIF* mutex, MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::BLOCKING, MutexGuard(MutexIF* mutex, MutexIF::TimeoutType timeoutType = MutexIF::TimeoutType::BLOCKING,
uint32_t timeoutMs = 0) uint32_t timeoutMs = 0, const char* context = nullptr)
: internalMutex(mutex) { : internalMutex(mutex) {
if (context == nullptr) {
context = "unknown";
}
if (mutex == nullptr) { if (mutex == nullptr) {
#if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::error << "MutexGuard: Passed mutex is invalid!" << std::endl; sif::error << "MutexGuard::" << context << ": Passed mutex is invalid!" << std::endl;
#else #else
sif::printError("MutexGuard: Passed mutex is invalid!\n"); sif::printError("MutexGuard::%s: Passed mutex is invalid!\n", context);
#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */
#endif /* FSFW_VERBOSE_LEVEL >= 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */
return; return;
@ -23,11 +26,11 @@ class MutexGuard {
#if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_VERBOSE_LEVEL >= 1
if (result == MutexIF::MUTEX_TIMEOUT) { if (result == MutexIF::MUTEX_TIMEOUT) {
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::error << "MutexGuard: Lock of mutex failed with timeout of " << timeoutMs sif::error << "MutexGuard::" << context << ": Lock of mutex failed with timeout of "
<< " milliseconds!" << std::endl; << timeoutMs << " milliseconds!" << std::endl;
#else #else
sif::printError("MutexGuard: Lock of mutex failed with timeout of %lu milliseconds\n", sif::printError("MutexGuard::%s: Lock of mutex failed with timeout of %lu milliseconds\n",
timeoutMs); context, timeoutMs);
#endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */ #endif /* FSFW_CPP_OSTREAM_ENABLED == 1 */
} else if (result != returnvalue::OK) { } else if (result != returnvalue::OK) {

View File

@ -19,32 +19,33 @@ 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 constexpr 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 constexpr Mode_t MODE_OFF = 0;
static const Submode_t SUBMODE_NONE = 0; //!< To avoid checks against magic number "0".
static constexpr Mode_t MODE_INVALID = -1;
static constexpr Mode_t MODE_UNDEFINED = -2;
//! 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

@ -1,43 +1,42 @@
#ifndef FSFW_MODES_MODEMESSAGE_H_ #ifndef FSFW_MODES_MODEMESSAGE_H_
#define FSFW_MODES_MODEMESSAGE_H_ #define FSFW_MODES_MODEMESSAGE_H_
#include "../ipc/CommandMessage.h" #include "fsfw/ipc/CommandMessage.h"
typedef uint32_t Mode_t; typedef uint32_t Mode_t;
typedef uint8_t Submode_t; typedef uint8_t Submode_t;
class ModeMessage { class ModeMessage {
private:
ModeMessage();
public: public:
static const uint8_t MESSAGE_ID = messagetypes::MODE_COMMAND; static const uint8_t MESSAGE_ID = messagetypes::MODE_COMMAND;
static const Command_t CMD_MODE_COMMAND = //!> Command to set the specified Mode, replies are: REPLY_MODE_REPLY,
MAKE_COMMAND_ID(0x01); //!> Command to set the specified Mode, replies are: REPLY_MODE_REPLY, //! REPLY_WRONG_MODE_REPLY, and REPLY_REJECTED; don't add any replies,
//! REPLY_WRONG_MODE_REPLY, and REPLY_REJECTED; don't add any replies, //! as this will break the subsystem mode machine!!
//! as this will break the subsystem mode machine!! static const Command_t CMD_MODE_COMMAND = MAKE_COMMAND_ID(0x01);
static const Command_t CMD_MODE_COMMAND_FORCED = MAKE_COMMAND_ID( //!> Command to set the specified Mode, regardless of external control flag, replies
0xF1); //!> Command to set the specified Mode, regardless of external control flag, replies //! are: REPLY_MODE_REPLY, REPLY_WRONG_MODE_REPLY, and REPLY_REJECTED; don't add any
//! are: REPLY_MODE_REPLY, REPLY_WRONG_MODE_REPLY, and REPLY_REJECTED; don't add any //! replies, as this will break the subsystem mode machine!!
//! replies, as this will break the subsystem mode machine!! static const Command_t CMD_MODE_COMMAND_FORCED = MAKE_COMMAND_ID(0xF1);
static const Command_t REPLY_MODE_REPLY = //!> Reply to a CMD_MODE_COMMAND or CMD_MODE_READ
MAKE_COMMAND_ID(0x02); //!> Reply to a CMD_MODE_COMMAND or CMD_MODE_READ static const Command_t REPLY_MODE_REPLY = MAKE_COMMAND_ID(0x02);
static const Command_t REPLY_MODE_INFO = //!> Unrequested info about the current mode (used for composites to
MAKE_COMMAND_ID(0x03); //!> Unrequested info about the current mode (used for composites to //! inform their container of a changed mode)
//! inform their container of a changed mode) static const Command_t REPLY_MODE_INFO = MAKE_COMMAND_ID(0x03);
static const Command_t REPLY_CANT_REACH_MODE = MAKE_COMMAND_ID( //!> Reply in case a mode command can't be executed. Par1: returnCode, Par2: 0
0x04); //!> Reply in case a mode command can't be executed. Par1: returnCode, Par2: 0 static const Command_t REPLY_CANT_REACH_MODE = MAKE_COMMAND_ID(0x04);
static const Command_t REPLY_WRONG_MODE_REPLY = //!> Reply to a CMD_MODE_COMMAND, indicating that a mode was commanded
MAKE_COMMAND_ID(0x05); //!> Reply to a CMD_MODE_COMMAND, indicating that a mode was commanded //! and a transition started but was aborted; the parameters contain
//! and a transition started but was aborted; the parameters contain //! the mode that was reached
//! the mode that was reached static const Command_t REPLY_WRONG_MODE_REPLY = MAKE_COMMAND_ID(0x05);
static const Command_t CMD_MODE_READ = MAKE_COMMAND_ID( //!> Command to read the current mode and reply with a REPLY_MODE_REPLY
0x06); //!> Command to read the current mode and reply with a REPLY_MODE_REPLY static const Command_t CMD_MODE_READ = MAKE_COMMAND_ID(0x06);
static const Command_t CMD_MODE_ANNOUNCE = MAKE_COMMAND_ID( //!> Command to trigger an ModeInfo Event. This command does NOT have a reply.
0x07); //!> Command to trigger an ModeInfo Event. This command does NOT have a reply. static const Command_t CMD_MODE_ANNOUNCE = MAKE_COMMAND_ID(0x07);
static const Command_t CMD_MODE_ANNOUNCE_RECURSIVELY = //!> Command to trigger an ModeInfo Event and to send this command to
MAKE_COMMAND_ID(0x08); //!> Command to trigger an ModeInfo Event and to send this command to //! every child. This command does NOT have a reply.
//! every child. This command does NOT have a reply. static const Command_t CMD_MODE_ANNOUNCE_RECURSIVELY = MAKE_COMMAND_ID(0x08);
ModeMessage() = delete;
static Mode_t getMode(const CommandMessage* message); static Mode_t getMode(const CommandMessage* message);
static Submode_t getSubmode(const CommandMessage* message); static Submode_t getSubmode(const CommandMessage* message);

View File

@ -117,7 +117,9 @@ void ObjectManager::initialize() {
"initialize with code 0x" "initialize with code 0x"
<< result << std::dec << std::setfill(' ') << std::endl; << result << std::dec << std::setfill(' ') << std::endl;
#else #else
sif::printError("ObjectManager::initialize: Object 0x%08x failed to initialize with code 0x%04x\n", var, result); sif::printError(
"ObjectManager::initialize: Object 0x%08x failed to initialize with code 0x%04x\n", var,
result);
#endif #endif
errorCount++; errorCount++;
} }

View File

@ -15,6 +15,7 @@ enum framework_objects : object_id_t {
PUS_SERVICE_8_FUNCTION_MGMT = 0x53000008, PUS_SERVICE_8_FUNCTION_MGMT = 0x53000008,
PUS_SERVICE_9_TIME_MGMT = 0x53000009, PUS_SERVICE_9_TIME_MGMT = 0x53000009,
PUS_SERVICE_11_TC_SCHEDULER = 0x53000011, PUS_SERVICE_11_TC_SCHEDULER = 0x53000011,
PUS_SERVICE_15_TM_STORAGE = 0x53000015,
PUS_SERVICE_17_TEST = 0x53000017, PUS_SERVICE_17_TEST = 0x53000017,
PUS_SERVICE_20_PARAMETERS = 0x53000020, PUS_SERVICE_20_PARAMETERS = 0x53000020,
PUS_SERVICE_200_MODE_MGMT = 0x53000200, PUS_SERVICE_200_MODE_MGMT = 0x53000200,

View File

@ -41,6 +41,7 @@ int TcpIpBase::closeSocket(socket_t socket) {
#elif defined(PLATFORM_UNIX) #elif defined(PLATFORM_UNIX)
return close(socket); return close(socket);
#endif #endif
return -1;
} }
int TcpIpBase::getLastSocketError() { int TcpIpBase::getLastSocketError() {
@ -49,4 +50,5 @@ int TcpIpBase::getLastSocketError() {
#elif defined(PLATFORM_UNIX) #elif defined(PLATFORM_UNIX)
return errno; return errno;
#endif #endif
return 0;
} }

View File

@ -16,9 +16,9 @@
#endif #endif
TcpTmTcBridge::TcpTmTcBridge(object_id_t objectId, object_id_t tcDestination, object_id_t tmStoreId, TcpTmTcBridge::TcpTmTcBridge(object_id_t objectId, object_id_t tcDestination,
object_id_t tcStoreId) uint32_t msgQueueDepth, object_id_t tmStoreId, object_id_t tcStoreId)
: TmTcBridge("TCP TMTC Bridge", objectId, tcDestination, tmStoreId, tcStoreId) { : TmTcBridge("TCP TMTC Bridge", objectId, tcDestination, msgQueueDepth, tmStoreId, tcStoreId) {
mutex = MutexFactory::instance()->createMutex(); mutex = MutexFactory::instance()->createMutex();
// Connection is always up, TM is requested by connecting to server and receiving packets // Connection is always up, TM is requested by connecting to server and receiving packets
registerCommConnect(); registerCommConnect();

View File

@ -38,7 +38,7 @@ class TcpTmTcBridge : public TmTcBridge {
* @param tmStoreId TM store object ID. It is recommended to the default object ID * @param tmStoreId TM store object ID. It is recommended to the default object ID
* @param tcStoreId TC store object ID. It is recommended to the default object ID * @param tcStoreId TC store object ID. It is recommended to the default object ID
*/ */
TcpTmTcBridge(object_id_t objectId, object_id_t tcDestination, TcpTmTcBridge(object_id_t objectId, object_id_t tcDestination, uint32_t msgQueueDepth,
object_id_t tmStoreId = objects::TM_STORE, object_id_t tmStoreId = objects::TM_STORE,
object_id_t tcStoreId = objects::TC_STORE); object_id_t tcStoreId = objects::TC_STORE);
virtual ~TcpTmTcBridge(); virtual ~TcpTmTcBridge();

View File

@ -283,6 +283,8 @@ ReturnValue_t TcpTmTcServer::handleTmSending(socket_t connSocket, bool& tmSent)
ConstStorageAccessor storeAccessor(storeId); ConstStorageAccessor storeAccessor(storeId);
ReturnValue_t result = tmStore->getData(storeId, storeAccessor); ReturnValue_t result = tmStore->getData(storeId, storeAccessor);
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
// Invalid entry, pop FIFO
tmtcBridge->tmFifo->pop();
return result; return result;
} }
if (wiretappingEnabled) { if (wiretappingEnabled) {

View File

@ -79,6 +79,7 @@ class TcpTmTcServer : public SystemObject, public TcpIpBase, public ExecutableOb
*/ */
bool reusePort = false; bool reusePort = false;
}; };
enum class ReceptionModes { SPACE_PACKETS }; enum class ReceptionModes { SPACE_PACKETS };
static const std::string DEFAULT_SERVER_PORT; static const std::string DEFAULT_SERVER_PORT;

View File

@ -20,9 +20,9 @@
const std::string UdpTmTcBridge::DEFAULT_SERVER_PORT = tcpip::DEFAULT_SERVER_PORT; const std::string UdpTmTcBridge::DEFAULT_SERVER_PORT = tcpip::DEFAULT_SERVER_PORT;
UdpTmTcBridge::UdpTmTcBridge(object_id_t objectId, object_id_t tcDestination, UdpTmTcBridge::UdpTmTcBridge(object_id_t objectId, object_id_t tcDestination,
const std::string &udpServerPort_, object_id_t tmStoreId, uint32_t msgQueueDepth, const std::string &udpServerPort_,
object_id_t tcStoreId) object_id_t tmStoreId, object_id_t tcStoreId)
: TmTcBridge("UDP TMTC Bridge", objectId, tcDestination, tmStoreId, tcStoreId) { : TmTcBridge("UDP TMTC Bridge", objectId, tcDestination, msgQueueDepth, tmStoreId, tcStoreId) {
if (udpServerPort_.empty()) { if (udpServerPort_.empty()) {
udpServerPort = DEFAULT_SERVER_PORT; udpServerPort = DEFAULT_SERVER_PORT;
} else { } else {
@ -126,10 +126,7 @@ ReturnValue_t UdpTmTcBridge::sendTm(const uint8_t *data, size_t dataLen) {
tcpip::handleError(tcpip::Protocol::UDP, tcpip::ErrorSources::SENDTO_CALL); tcpip::handleError(tcpip::Protocol::UDP, tcpip::ErrorSources::SENDTO_CALL);
} }
#if FSFW_CPP_OSTREAM_ENABLED == 1 && FSFW_UDP_SEND_WIRETAPPING_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1 && FSFW_UDP_SEND_WIRETAPPING_ENABLED == 1
sif::debug << "TmTcUdpBridge::sendTm: " << bytesSent sif::debug << "TmTcUdpBridge::sendTm: " << bytesSent << " bytes were sent" << std::endl;
<< " bytes were"
" sent."
<< std::endl;
#endif #endif
return returnvalue::OK; return returnvalue::OK;
} }

View File

@ -29,7 +29,7 @@ class UdpTmTcBridge : public TmTcBridge, public TcpIpBase {
/* The ports chosen here should not be used by any other process. */ /* The ports chosen here should not be used by any other process. */
static const std::string DEFAULT_SERVER_PORT; static const std::string DEFAULT_SERVER_PORT;
UdpTmTcBridge(object_id_t objectId, object_id_t tcDestination, UdpTmTcBridge(object_id_t objectId, object_id_t tcDestination, uint32_t msgQueueDepth,
const std::string& udpServerPort = "", object_id_t tmStoreId = objects::TM_STORE, const std::string& udpServerPort = "", object_id_t tmStoreId = objects::TM_STORE,
object_id_t tcStoreId = objects::TC_STORE); object_id_t tcStoreId = objects::TC_STORE);
~UdpTmTcBridge() override; ~UdpTmTcBridge() override;

View File

@ -47,7 +47,32 @@ ReturnValue_t Clock::setClock(const timeval* time) {
return returnvalue::OK; return returnvalue::OK;
} }
ReturnValue_t Clock::getClock_timeval(timeval* time) { ReturnValue_t Clock::getClockMonotonic(timeval* time) {
#if defined(PLATFORM_WIN)
// TODO: Implement with std::chrono::steady_clock.. or in some other way. I am not even sure
// whether this is possible with steady_clock. The conversion we have to do here just to be
// generic is kind of awkward..
return returnvalue::FAILED;
#elif defined(PLATFORM_UNIX)
timespec timeMonotonic;
int status = clock_gettime(CLOCK_MONOTONIC_RAW, &timeMonotonic);
if (status != 0) {
return returnvalue::FAILED;
}
time->tv_sec = timeMonotonic.tv_sec;
time->tv_usec = timeMonotonic.tv_nsec / 1000.0;
return returnvalue::OK;
#else
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "Clock::getUptime: Not implemented for found OS!" << std::endl;
#else
sif::printWarning("Clock::getUptime: Not implemented for found OS!\n");
#endif
return returnvalue::FAILED;
#endif
}
ReturnValue_t Clock::getClock(timeval* time) {
#if defined(PLATFORM_WIN) #if defined(PLATFORM_WIN)
auto now = std::chrono::system_clock::now(); auto now = std::chrono::system_clock::now();
auto secondsChrono = std::chrono::time_point_cast<std::chrono::seconds>(now); auto secondsChrono = std::chrono::time_point_cast<std::chrono::seconds>(now);
@ -75,6 +100,8 @@ ReturnValue_t Clock::getClock_timeval(timeval* time) {
#endif #endif
} }
ReturnValue_t Clock::getClock_timeval(timeval* time) { return Clock::getClock(time); }
ReturnValue_t Clock::getClock_usecs(uint64_t* time) { ReturnValue_t Clock::getClock_usecs(uint64_t* time) {
if (time == nullptr) { if (time == nullptr) {
return returnvalue::FAILED; return returnvalue::FAILED;

View File

@ -20,16 +20,18 @@ TaskFactory::~TaskFactory() = default;
TaskFactory* TaskFactory::instance() { return TaskFactory::factoryInstance; } TaskFactory* TaskFactory::instance() { return TaskFactory::factoryInstance; }
PeriodicTaskIF* TaskFactory::createPeriodicTask( PeriodicTaskIF* TaskFactory::createPeriodicTask(TaskName name_, TaskPriority taskPriority_,
TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_, TaskStackSize stackSize_,
TaskPeriod periodInSeconds_, TaskDeadlineMissedFunction deadLineMissedFunction_) { TaskPeriod periodInSeconds_,
TaskDeadlineMissedFunction deadLineMissedFunction_,
void* args) {
return new PeriodicTask(name_, taskPriority_, stackSize_, periodInSeconds_, return new PeriodicTask(name_, taskPriority_, stackSize_, periodInSeconds_,
deadLineMissedFunction_); deadLineMissedFunction_);
} }
FixedTimeslotTaskIF* TaskFactory::createFixedTimeslotTask( FixedTimeslotTaskIF* TaskFactory::createFixedTimeslotTask(
TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_, TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_,
TaskPeriod periodInSeconds_, TaskDeadlineMissedFunction deadLineMissedFunction_) { TaskPeriod periodInSeconds_, TaskDeadlineMissedFunction deadLineMissedFunction_, void* args) {
return new FixedTimeslotTask(name_, taskPriority_, stackSize_, periodInSeconds_, return new FixedTimeslotTask(name_, taskPriority_, stackSize_, periodInSeconds_,
deadLineMissedFunction_); deadLineMissedFunction_);
} }

View File

@ -42,7 +42,7 @@ ReturnValue_t Clock::setClock(const timeval* time) {
return returnvalue::OK; return returnvalue::OK;
} }
ReturnValue_t Clock::getClock_timeval(timeval* time) { ReturnValue_t Clock::getClock(timeval* time) {
timespec timeUnix{}; timespec timeUnix{};
int status = clock_gettime(CLOCK_REALTIME, &timeUnix); int status = clock_gettime(CLOCK_REALTIME, &timeUnix);
if (status != 0) { if (status != 0) {
@ -53,6 +53,8 @@ ReturnValue_t Clock::getClock_timeval(timeval* time) {
return returnvalue::OK; return returnvalue::OK;
} }
ReturnValue_t Clock::getClock_timeval(timeval* time) { return Clock::getClock(time); }
ReturnValue_t Clock::getClock_usecs(uint64_t* time) { ReturnValue_t Clock::getClock_usecs(uint64_t* time) {
timeval timeVal{}; timeval timeVal{};
ReturnValue_t result = getClock_timeval(&timeVal); ReturnValue_t result = getClock_timeval(&timeVal);
@ -64,6 +66,17 @@ ReturnValue_t Clock::getClock_usecs(uint64_t* time) {
return returnvalue::OK; return returnvalue::OK;
} }
ReturnValue_t Clock::getClockMonotonic(timeval* time) {
timespec timeMonotonic{};
int status = clock_gettime(CLOCK_MONOTONIC_RAW, &timeMonotonic);
if (status != 0) {
return returnvalue::FAILED;
}
time->tv_sec = timeMonotonic.tv_sec;
time->tv_usec = timeMonotonic.tv_nsec / 1000.0;
return returnvalue::OK;
}
timeval Clock::getUptime() { timeval Clock::getUptime() {
timeval uptime{}; timeval uptime{};
auto result = getUptime(&uptime); auto result = getUptime(&uptime);

View File

@ -7,10 +7,15 @@
const size_t PeriodicTaskIF::MINIMUM_STACK_SIZE = PTHREAD_STACK_MIN; const size_t PeriodicTaskIF::MINIMUM_STACK_SIZE = PTHREAD_STACK_MIN;
FixedTimeslotTask::FixedTimeslotTask(const char* name_, TaskPriority priority_, size_t stackSize_, FixedTimeslotTask::FixedTimeslotTask(const char* name_, TaskPriority priority_, size_t stackSize_,
TaskPeriod periodSeconds_, TaskDeadlineMissedFunction dlmFunc_) TaskPeriod periodSeconds_, TaskDeadlineMissedFunction dlmFunc_,
PosixThreadArgs* args)
: FixedTimeslotTaskBase(periodSeconds_, dlmFunc_), : FixedTimeslotTaskBase(periodSeconds_, dlmFunc_),
posixThread(name_, priority_, stackSize_), posixThread(name_, SchedulingPolicy::REGULAR, priority_, stackSize_),
started(false) {} started(false) {
if (args != nullptr) {
posixThread.setSchedPolicy(args->policy);
}
}
void* FixedTimeslotTask::taskEntryPoint(void* arg) { void* FixedTimeslotTask::taskEntryPoint(void* arg) {
// The argument is re-interpreted as PollingTask. // The argument is re-interpreted as PollingTask.

View File

@ -23,7 +23,8 @@ class FixedTimeslotTask : public FixedTimeslotTaskBase {
* @param deadlineMissedFunc_ * @param deadlineMissedFunc_
*/ */
FixedTimeslotTask(const char* name_, TaskPriority priority_, size_t stackSize_, FixedTimeslotTask(const char* name_, TaskPriority priority_, size_t stackSize_,
TaskPeriod periodSeconds_, TaskDeadlineMissedFunction dlmFunc_); TaskPeriod periodSeconds_, TaskDeadlineMissedFunction dlmFunc_,
PosixThreadArgs* args);
~FixedTimeslotTask() override = default; ~FixedTimeslotTask() override = default;
ReturnValue_t startTask() override; ReturnValue_t startTask() override;

View File

@ -4,10 +4,15 @@
#include "fsfw/tasks/ExecutableObjectIF.h" #include "fsfw/tasks/ExecutableObjectIF.h"
PeriodicPosixTask::PeriodicPosixTask(const char* name_, int priority_, size_t stackSize_, PeriodicPosixTask::PeriodicPosixTask(const char* name_, int priority_, size_t stackSize_,
TaskPeriod period_, TaskDeadlineMissedFunction dlmFunc_) TaskPeriod period_, TaskDeadlineMissedFunction dlmFunc_,
PosixThreadArgs* args)
: PeriodicTaskBase(period_, dlmFunc_), : PeriodicTaskBase(period_, dlmFunc_),
posixThread(name_, priority_, stackSize_), posixThread(name_, SchedulingPolicy::REGULAR, priority_, stackSize_),
started(false) {} started(false) {
if (args != nullptr) {
posixThread.setSchedPolicy(args->policy);
}
}
void* PeriodicPosixTask::taskEntryPoint(void* arg) { void* PeriodicPosixTask::taskEntryPoint(void* arg) {
// The argument is re-interpreted as PollingTask. // The argument is re-interpreted as PollingTask.

View File

@ -24,7 +24,7 @@ class PeriodicPosixTask : public PeriodicTaskBase {
* @param deadlineMissedFunc_ * @param deadlineMissedFunc_
*/ */
PeriodicPosixTask(const char* name_, int priority_, size_t stackSize_, TaskPeriod period_, PeriodicPosixTask(const char* name_, int priority_, size_t stackSize_, TaskPeriod period_,
TaskDeadlineMissedFunction dlmFunc_); TaskDeadlineMissedFunction dlmFunc_, PosixThreadArgs* args);
~PeriodicPosixTask() override = default; ~PeriodicPosixTask() override = default;
/** /**

View File

@ -7,8 +7,9 @@
#include "fsfw/osal/linux/unixUtility.h" #include "fsfw/osal/linux/unixUtility.h"
#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/serviceinterface/ServiceInterface.h"
PosixThread::PosixThread(const char* name_, int priority_, size_t stackSize_) PosixThread::PosixThread(const char* name_, SchedulingPolicy schedPolciy, int priority_,
: thread(0), priority(priority_), stackSize(stackSize_) { size_t stackSize_)
: thread(0), schedPolicy(schedPolciy), priority(priority_), stackSize(stackSize_) {
name[0] = '\0'; name[0] = '\0';
std::strncat(name, name_, PTHREAD_MAX_NAMELEN - 1); std::strncat(name, name_, PTHREAD_MAX_NAMELEN - 1);
} }
@ -178,20 +179,30 @@ void PosixThread::createTask(void* (*fnc_)(void*), void* arg_) {
#ifndef FSFW_USE_REALTIME_FOR_LINUX #ifndef FSFW_USE_REALTIME_FOR_LINUX
#error "Please define FSFW_USE_REALTIME_FOR_LINUX with either 0 or 1" #error "Please define FSFW_USE_REALTIME_FOR_LINUX with either 0 or 1"
#endif #endif
if (schedPolicy == SchedulingPolicy::RR) {
// RR -> This needs root privileges for the process
#if FSFW_USE_REALTIME_FOR_LINUX == 1 #if FSFW_USE_REALTIME_FOR_LINUX == 1
// FIFO -> This needs root privileges for the process status = pthread_attr_setschedpolicy(&attributes, SCHED_RR);
status = pthread_attr_setschedpolicy(&attributes, SCHED_FIFO); if (status != 0) {
if (status != 0) { utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_setschedpolicy");
utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_setschedpolicy"); }
sched_param scheduleParams;
scheduleParams.sched_priority = priority;
status = pthread_attr_setschedparam(&attributes, &scheduleParams);
if (status != 0) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "PosixThread: Setting priority failed" << std::endl;
#endif
}
#else
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning
<< "Real time priorities are only allowed if FSFW_USE_REALTIME_FOR_LINUX is set to 1"
<< std::endl;
#endif
#endif
} }
sched_param scheduleParams;
scheduleParams.__sched_priority = priority;
status = pthread_attr_setschedparam(&attributes, &scheduleParams);
if (status != 0) {
utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_setschedparam");
}
#endif
// Set Signal Mask for suspend until startTask is called // Set Signal Mask for suspend until startTask is called
sigset_t waitSignal; sigset_t waitSignal;
sigemptyset(&waitSignal); sigemptyset(&waitSignal);
@ -243,3 +254,5 @@ void PosixThread::createTask(void* (*fnc_)(void*), void* arg_) {
utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_destroy"); utility::printUnixErrorGeneric(CLASS_NAME, "createTask", "pthread_attr_destroy");
} }
} }
void PosixThread::setSchedPolicy(SchedulingPolicy policy) { this->schedPolicy = policy; }

View File

@ -9,10 +9,15 @@
#include "../../returnvalues/returnvalue.h" #include "../../returnvalues/returnvalue.h"
enum SchedulingPolicy { REGULAR, RR };
struct PosixThreadArgs {
SchedulingPolicy policy = SchedulingPolicy::REGULAR;
};
class PosixThread { class PosixThread {
public: public:
static constexpr uint8_t PTHREAD_MAX_NAMELEN = 16; static constexpr uint8_t PTHREAD_MAX_NAMELEN = 16;
PosixThread(const char* name_, int priority_, size_t stackSize_); PosixThread(const char* name_, SchedulingPolicy schedPolicy, int priority_, size_t stackSize_);
virtual ~PosixThread(); virtual ~PosixThread();
/** /**
* Set the Thread to sleep state * Set the Thread to sleep state
@ -20,6 +25,9 @@ class PosixThread {
* @return Returns Failed if sleep fails * @return Returns Failed if sleep fails
*/ */
static ReturnValue_t sleep(uint64_t ns); static ReturnValue_t sleep(uint64_t ns);
void setSchedPolicy(SchedulingPolicy policy);
/** /**
* @brief Function to suspend the task until SIGUSR1 was received * @brief Function to suspend the task until SIGUSR1 was received
* *
@ -72,6 +80,7 @@ class PosixThread {
private: private:
char name[PTHREAD_MAX_NAMELEN]; char name[PTHREAD_MAX_NAMELEN];
SchedulingPolicy schedPolicy;
int priority; int priority;
size_t stackSize = 0; size_t stackSize = 0;

View File

@ -12,18 +12,20 @@ TaskFactory::~TaskFactory() = default;
TaskFactory* TaskFactory::instance() { return TaskFactory::factoryInstance; } TaskFactory* TaskFactory::instance() { return TaskFactory::factoryInstance; }
PeriodicTaskIF* TaskFactory::createPeriodicTask( PeriodicTaskIF* TaskFactory::createPeriodicTask(TaskName name_, TaskPriority taskPriority_,
TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_, TaskStackSize stackSize_,
TaskPeriod periodInSeconds_, TaskDeadlineMissedFunction deadLineMissedFunction_) { TaskPeriod periodInSeconds_,
TaskDeadlineMissedFunction deadLineMissedFunction_,
void* args) {
return new PeriodicPosixTask(name_, taskPriority_, stackSize_, periodInSeconds_, return new PeriodicPosixTask(name_, taskPriority_, stackSize_, periodInSeconds_,
deadLineMissedFunction_); deadLineMissedFunction_, reinterpret_cast<PosixThreadArgs*>(args));
} }
FixedTimeslotTaskIF* TaskFactory::createFixedTimeslotTask( FixedTimeslotTaskIF* TaskFactory::createFixedTimeslotTask(
TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_, TaskName name_, TaskPriority taskPriority_, TaskStackSize stackSize_,
TaskPeriod periodInSeconds_, TaskDeadlineMissedFunction deadLineMissedFunction_) { TaskPeriod periodInSeconds_, TaskDeadlineMissedFunction deadLineMissedFunction_, void* args) {
return new FixedTimeslotTask(name_, taskPriority_, stackSize_, periodInSeconds_, return new FixedTimeslotTask(name_, taskPriority_, stackSize_, periodInSeconds_,
deadLineMissedFunction_); deadLineMissedFunction_, reinterpret_cast<PosixThreadArgs*>(args));
} }
ReturnValue_t TaskFactory::deleteTask(PeriodicTaskIF* task) { ReturnValue_t TaskFactory::deleteTask(PeriodicTaskIF* task) {

View File

@ -66,7 +66,8 @@ class HasParametersIF {
* @param newValues * @param newValues
* @param startAtIndex Linear index, runs left to right, top to bottom for * @param startAtIndex Linear index, runs left to right, top to bottom for
* matrix indexes. * matrix indexes.
* @return * @return returnvalue::OK if parameter is valid and a set function of the parameter wrapper was
* called.
*/ */
virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueIdentifier, virtual ReturnValue_t getParameter(uint8_t domainId, uint8_t uniqueIdentifier,
ParameterWrapper *parameterWrapper, ParameterWrapper *parameterWrapper,

View File

@ -211,9 +211,13 @@ ReturnValue_t ParameterWrapper::copyFrom(const ParameterWrapper *from,
if (data == nullptr) { if (data == nullptr) {
#if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "ParameterWrapper::copyFrom: Called on read-only variable!" << std::endl; sif::warning << "ParameterWrapper::copyFrom: Called on read-only variable or "
"data pointer not set"
<< std::endl;
#else #else
sif::printWarning("ParameterWrapper::copyFrom: Called on read-only variable!\n"); sif::printWarning(
"ParameterWrapper::copyFrom: Called on read-only variable "
"or data pointer not set\n");
#endif #endif
#endif /* FSFW_VERBOSE_LEVEL >= 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */
return READONLY; return READONLY;
@ -222,9 +226,9 @@ ReturnValue_t ParameterWrapper::copyFrom(const ParameterWrapper *from,
if (from->readonlyData == nullptr) { if (from->readonlyData == nullptr) {
#if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "ParameterWrapper::copyFrom: Source not set!" << std::endl; sif::warning << "ParameterWrapper::copyFrom: Source not set" << std::endl;
#else #else
sif::printWarning("ParameterWrapper::copyFrom: Source not set!\n"); sif::printWarning("ParameterWrapper::copyFrom: Source not set\n");
#endif #endif
#endif /* FSFW_VERBOSE_LEVEL >= 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */
return SOURCE_NOT_SET; return SOURCE_NOT_SET;
@ -233,9 +237,9 @@ ReturnValue_t ParameterWrapper::copyFrom(const ParameterWrapper *from,
if (type != from->type) { if (type != from->type) {
#if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "ParameterWrapper::copyFrom: Datatype missmatch!" << std::endl; sif::warning << "ParameterWrapper::copyFrom: Datatype missmatch" << std::endl;
#else #else
sif::printWarning("ParameterWrapper::copyFrom: Datatype missmatch!\n"); sif::printWarning("ParameterWrapper::copyFrom: Datatype missmatch\n");
#endif #endif
#endif /* FSFW_VERBOSE_LEVEL >= 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */
return DATATYPE_MISSMATCH; return DATATYPE_MISSMATCH;
@ -245,9 +249,9 @@ ReturnValue_t ParameterWrapper::copyFrom(const ParameterWrapper *from,
if (rows == 0 or columns == 0) { if (rows == 0 or columns == 0) {
#if FSFW_VERBOSE_LEVEL >= 1 #if FSFW_VERBOSE_LEVEL >= 1
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "ParameterWrapper::copyFrom: Columns or rows zero!" << std::endl; sif::warning << "ParameterWrapper::copyFrom: Columns or rows zero" << std::endl;
#else #else
sif::printWarning("ParameterWrapper::copyFrom: Columns or rows zero!\n"); sif::printWarning("ParameterWrapper::copyFrom: Columns or rows zero\n");
#endif #endif
#endif /* FSFW_VERBOSE_LEVEL >= 1 */ #endif /* FSFW_VERBOSE_LEVEL >= 1 */
return COLUMN_OR_ROWS_ZERO; return COLUMN_OR_ROWS_ZERO;

View File

@ -6,7 +6,11 @@ DummyPowerSwitcher::DummyPowerSwitcher(object_id_t objectId, size_t numberOfSwit
: SystemObject(objectId, registerGlobally), : SystemObject(objectId, registerGlobally),
switcherList(numberOfSwitches), switcherList(numberOfSwitches),
fuseList(numberOfFuses), fuseList(numberOfFuses),
switchDelayMs(switchDelayMs) {} switchDelayMs(switchDelayMs) {
for (auto &switchState : switcherList) {
switchState = PowerSwitchIF::SWITCH_UNKNOWN;
}
}
void DummyPowerSwitcher::setInitialSwitcherList(std::vector<ReturnValue_t> switcherList) { void DummyPowerSwitcher::setInitialSwitcherList(std::vector<ReturnValue_t> switcherList) {
this->switcherList = switcherList; this->switcherList = switcherList;

View File

@ -2,8 +2,9 @@
#include <fsfw/ipc/QueueFactory.h> #include <fsfw/ipc/QueueFactory.h>
#include <fsfw/power/PowerSwitchIF.h> #include <fsfw/power/PowerSwitchIF.h>
#include <fsfw/subsystem/helper.h>
PowerSwitcherComponent::PowerSwitcherComponent(object_id_t objectId, PowerSwitchIF *pwrSwitcher, PowerSwitcherComponent::PowerSwitcherComponent(object_id_t objectId, PowerSwitchIF* pwrSwitcher,
power::Switch_t pwrSwitch) power::Switch_t pwrSwitch)
: SystemObject(objectId), : SystemObject(objectId),
switcher(pwrSwitcher, pwrSwitch), switcher(pwrSwitcher, pwrSwitch),
@ -28,6 +29,9 @@ ReturnValue_t PowerSwitcherComponent::performOperation(uint8_t opCode) {
continue; continue;
} }
} }
if (getHealth() == FAULTY) {
performFaultyOperation();
}
if (switcher.active()) { if (switcher.active()) {
switcher.doStateMachine(); switcher.doStateMachine();
auto currState = switcher.getState(); auto currState = switcher.getState();
@ -54,7 +58,7 @@ ReturnValue_t PowerSwitcherComponent::initialize() {
MessageQueueId_t PowerSwitcherComponent::getCommandQueue() const { return queue->getId(); } MessageQueueId_t PowerSwitcherComponent::getCommandQueue() const { return queue->getId(); }
void PowerSwitcherComponent::getMode(Mode_t *mode, Submode_t *submode) { void PowerSwitcherComponent::getMode(Mode_t* mode, Submode_t* submode) {
*mode = this->mode; *mode = this->mode;
*submode = this->submode; *submode = this->submode;
} }
@ -65,7 +69,7 @@ ReturnValue_t PowerSwitcherComponent::setHealth(HealthState health) {
} }
ReturnValue_t PowerSwitcherComponent::checkModeCommand(Mode_t mode, Submode_t submode, ReturnValue_t PowerSwitcherComponent::checkModeCommand(Mode_t mode, Submode_t submode,
uint32_t *msToReachTheMode) { uint32_t* msToReachTheMode) {
*msToReachTheMode = 5000; *msToReachTheMode = 5000;
if (mode != MODE_ON and mode != MODE_OFF) { if (mode != MODE_ON and mode != MODE_OFF) {
return TRANS_NOT_ALLOWED; return TRANS_NOT_ALLOWED;
@ -105,3 +109,17 @@ void PowerSwitcherComponent::setMode(Mode_t newMode, Submode_t newSubmode) {
} }
HasHealthIF::HealthState PowerSwitcherComponent::getHealth() { return healthHelper.getHealth(); } HasHealthIF::HealthState PowerSwitcherComponent::getHealth() { return healthHelper.getHealth(); }
const HasHealthIF* PowerSwitcherComponent::getOptHealthIF() const { return this; }
const HasModesIF& PowerSwitcherComponent::getModeIF() const { return *this; }
ReturnValue_t PowerSwitcherComponent::connectModeTreeParent(HasModeTreeChildrenIF& parent) {
return modetree::connectModeTreeParent(parent, *this, &healthHelper, modeHelper);
}
object_id_t PowerSwitcherComponent::getObjectId() const { return SystemObject::getObjectId(); }
ModeTreeChildIF& PowerSwitcherComponent::getModeTreeChildIF() { return *this; }
void PowerSwitcherComponent::performFaultyOperation() {}

View File

@ -1,5 +1,4 @@
#ifndef _FSFW_POWER_POWERSWITCHERCOMPONENT_H_ #pragma once
#define _FSFW_POWER_POWERSWITCHERCOMPONENT_H_
#include <fsfw/health/HasHealthIF.h> #include <fsfw/health/HasHealthIF.h>
#include <fsfw/health/HealthHelper.h> #include <fsfw/health/HealthHelper.h>
@ -8,6 +7,8 @@
#include <fsfw/objectmanager/SystemObject.h> #include <fsfw/objectmanager/SystemObject.h>
#include <fsfw/power/PowerSwitcher.h> #include <fsfw/power/PowerSwitcher.h>
#include <fsfw/power/definitions.h> #include <fsfw/power/definitions.h>
#include <fsfw/subsystem/ModeTreeChildIF.h>
#include <fsfw/subsystem/ModeTreeConnectionIF.h>
#include <fsfw/tasks/ExecutableObjectIF.h> #include <fsfw/tasks/ExecutableObjectIF.h>
class PowerSwitchIF; class PowerSwitchIF;
@ -24,17 +25,24 @@ class PowerSwitchIF;
*/ */
class PowerSwitcherComponent : public SystemObject, class PowerSwitcherComponent : public SystemObject,
public ExecutableObjectIF, public ExecutableObjectIF,
public ModeTreeChildIF,
public ModeTreeConnectionIF,
public HasModesIF, public HasModesIF,
public HasHealthIF { public HasHealthIF {
public: public:
PowerSwitcherComponent(object_id_t objectId, PowerSwitchIF *pwrSwitcher, PowerSwitcherComponent(object_id_t objectId, PowerSwitchIF *pwrSwitcher,
power::Switch_t pwrSwitch); power::Switch_t pwrSwitch);
private: ReturnValue_t connectModeTreeParent(HasModeTreeChildrenIF &parent) override;
MessageQueueIF *queue = nullptr; ModeTreeChildIF &getModeTreeChildIF() override;
protected:
PowerSwitcher switcher; PowerSwitcher switcher;
Mode_t mode = MODE_OFF; private:
MessageQueueIF *queue = nullptr;
Mode_t mode = MODE_UNDEFINED;
Submode_t submode = 0; Submode_t submode = 0;
ModeHelper modeHelper; ModeHelper modeHelper;
@ -42,20 +50,23 @@ class PowerSwitcherComponent : public SystemObject,
void setMode(Mode_t newMode, Submode_t newSubmode); void setMode(Mode_t newMode, Submode_t newSubmode);
virtual ReturnValue_t performOperation(uint8_t opCode) override; ReturnValue_t performOperation(uint8_t opCode) override;
ReturnValue_t initialize() override; ReturnValue_t initialize() override;
MessageQueueId_t getCommandQueue() const override; [[nodiscard]] MessageQueueId_t getCommandQueue() const override;
void getMode(Mode_t *mode, Submode_t *submode) override; void getMode(Mode_t *mode, Submode_t *submode) override;
ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode, ReturnValue_t checkModeCommand(Mode_t mode, Submode_t submode,
uint32_t *msToReachTheMode) override; uint32_t *msToReachTheMode) override;
void startTransition(Mode_t mode, Submode_t submode) override; void startTransition(Mode_t mode, Submode_t submode) override;
virtual void performFaultyOperation();
void setToExternalControl() override; void setToExternalControl() override;
void announceMode(bool recursive) override; void announceMode(bool recursive) override;
ReturnValue_t setHealth(HealthState health) override; ReturnValue_t setHealth(HealthState health) override;
HasHealthIF::HealthState getHealth() override; HasHealthIF::HealthState getHealth() override;
};
#endif /* _FSFW_POWER_POWERSWITCHERCOMPONENT_H_ */ [[nodiscard]] object_id_t getObjectId() const override;
[[nodiscard]] const HasHealthIF *getOptHealthIF() const override;
[[nodiscard]] const HasModesIF &getModeIF() const override;
};

View File

@ -79,7 +79,7 @@ inline ReturnValue_t Service11TelecommandScheduling<MAX_NUM_TCS>::performService
// NOTE: The iterator is increased in the loop here. Increasing the iterator as for-loop arg // NOTE: The iterator is increased in the loop here. Increasing the iterator as for-loop arg
// does not work in this case as we are deleting the current element here. // does not work in this case as we are deleting the current element here.
for (auto it = telecommandMap.begin(); it != telecommandMap.end();) { for (auto it = telecommandMap.begin(); it != telecommandMap.end();) {
if (it->first <= tNow.tv_sec) { if (it->first <= static_cast<uint32_t>(tNow.tv_sec)) {
if (schedulingEnabled) { if (schedulingEnabled) {
// release tc // release tc
TmTcMessage releaseMsg(it->second.storeAddr); TmTcMessage releaseMsg(it->second.storeAddr);
@ -160,7 +160,7 @@ inline ReturnValue_t Service11TelecommandScheduling<MAX_NUM_TCS>::doInsertActivi
// (See requirement for Time margin) // (See requirement for Time margin)
timeval tNow = {}; timeval tNow = {};
Clock::getClock_timeval(&tNow); Clock::getClock_timeval(&tNow);
if (timestamp - tNow.tv_sec <= RELEASE_TIME_MARGIN_SECONDS) { if (timestamp < static_cast<uint32_t>(tNow.tv_sec + RELEASE_TIME_MARGIN_SECONDS)) {
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "Service11TelecommandScheduling::doInsertActivity: Release time too close to " sif::warning << "Service11TelecommandScheduling::doInsertActivity: Release time too close to "
"current time" "current time"

View File

@ -1,5 +1,7 @@
#include "fsfw/pus/Service17Test.h" #include "fsfw/pus/Service17Test.h"
#include <fsfw/serialize/SerializeElement.h>
#include "fsfw/FSFW.h" #include "fsfw/FSFW.h"
#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/objectmanager/ObjectManager.h"
#include "fsfw/objectmanager/SystemObject.h" #include "fsfw/objectmanager/SystemObject.h"
@ -31,6 +33,15 @@ ReturnValue_t Service17Test::handleRequest(uint8_t subservice) {
} }
return tmHelper.storeAndSendTmPacket(); return tmHelper.storeAndSendTmPacket();
} }
case Subservice::PING_WITH_DATA: {
SerializeElement<uint32_t> receivedDataLen = currentPacket.getUserDataLen();
ReturnValue_t result =
tmHelper.prepareTmPacket(Subservice::PING_WITH_DATA_REPORT_WITH_SIZE, receivedDataLen);
if (result != returnvalue::OK) {
return result;
}
return tmHelper.storeAndSendTmPacket();
}
default: default:
return AcceptsTelecommandsIF::INVALID_SUBSERVICE; return AcceptsTelecommandsIF::INVALID_SUBSERVICE;
} }

View File

@ -32,6 +32,9 @@ class Service17Test : public PusServiceBase {
CONNECTION_TEST_REPORT = 2, CONNECTION_TEST_REPORT = 2,
//! [EXPORT] : [COMMAND] Trigger test reply and test event //! [EXPORT] : [COMMAND] Trigger test reply and test event
EVENT_TRIGGER_TEST = 128, EVENT_TRIGGER_TEST = 128,
PING_WITH_DATA = 129,
//! [EXPORT] : [COMMAND] Report which reports the sent user data size
PING_WITH_DATA_REPORT_WITH_SIZE = 130
}; };
explicit Service17Test(PsbParams params); explicit Service17Test(PsbParams params);

View File

@ -4,9 +4,10 @@
#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/objectmanager/ObjectManager.h"
#include "fsfw/pus/servicepackets/Service3Packets.h" #include "fsfw/pus/servicepackets/Service3Packets.h"
Service3Housekeeping::Service3Housekeeping(object_id_t objectId, uint16_t apid, uint8_t serviceId) Service3Housekeeping::Service3Housekeeping(object_id_t objectId, uint16_t apid, uint8_t serviceId,
: CommandingServiceBase(objectId, apid, "PUS 3 HK", serviceId, NUM_OF_PARALLEL_COMMANDS, uint32_t queueDepth, uint8_t numParallelCommands)
COMMAND_TIMEOUT_SECONDS) {} : CommandingServiceBase(objectId, apid, "PUS 3 HK", serviceId, numParallelCommands,
COMMAND_TIMEOUT_SECONDS, queueDepth) {}
Service3Housekeeping::~Service3Housekeeping() {} Service3Housekeeping::~Service3Housekeeping() {}
@ -208,17 +209,17 @@ ReturnValue_t Service3Housekeeping::handleReply(const CommandMessage* reply,
ReturnValue_t error = returnvalue::FAILED; ReturnValue_t error = returnvalue::FAILED;
HousekeepingMessage::getHkRequestFailureReply(reply, &error); HousekeepingMessage::getHkRequestFailureReply(reply, &error);
failureParameter2 = error; failureParameter2 = error;
return CommandingServiceBase::EXECUTION_COMPLETE; return returnvalue::FAILED;
} }
default: default:
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "Service3Housekeeping::handleReply: Invalid reply with " sif::warning << "Service3Housekeeping::handleReply: Invalid reply with "
<< "reply command " << command << "!" << std::endl; << "reply command " << command << std::endl;
#else #else
sif::printWarning( sif::printWarning(
"Service3Housekeeping::handleReply: Invalid reply with " "Service3Housekeeping::handleReply: Invalid reply with "
"reply command %hu!\n", "reply command %hu\n",
command); command);
#endif #endif
return CommandingServiceBase::INVALID_REPLY; return CommandingServiceBase::INVALID_REPLY;
@ -248,19 +249,28 @@ void Service3Housekeeping::handleUnrequestedReply(CommandMessage* reply) {
case (HousekeepingMessage::HK_REQUEST_FAILURE): { case (HousekeepingMessage::HK_REQUEST_FAILURE): {
break; break;
} }
case (CommandMessage::REPLY_REJECTED): {
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "Service3Housekeeping::handleUnrequestedReply: Unexpected reply "
"rejected with error code"
<< reply->getParameter() << std::endl;
#else
#endif
break;
}
default: { default: {
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "Service3Housekeeping::handleUnrequestedReply: Invalid reply with reply " sif::warning << "Service3Housekeeping::handleUnrequestedReply: Invalid reply with reply "
"command " "command "
<< command << "!" << std::endl; << command << "" << std::endl;
#else #else
sif::printWarning( sif::printWarning(
"Service3Housekeeping::handleUnrequestedReply: Invalid reply with " "Service3Housekeeping::handleUnrequestedReply: Invalid reply with "
"reply command %hu!\n", "reply command %hu\n",
command); command);
#endif #endif
return; break;
} }
} }
@ -275,6 +285,7 @@ void Service3Housekeeping::handleUnrequestedReply(CommandMessage* reply) {
"Could not generate reply!\n"); "Could not generate reply!\n");
#endif #endif
} }
CommandingServiceBase::handleUnrequestedReply(reply);
} }
MessageQueueId_t Service3Housekeeping::getHkQueue() const { return commandQueue->getId(); } MessageQueueId_t Service3Housekeeping::getHkQueue() const { return commandQueue->getId(); }

View File

@ -28,7 +28,8 @@ class Service3Housekeeping : public CommandingServiceBase, public AcceptsHkPacke
static constexpr uint8_t NUM_OF_PARALLEL_COMMANDS = 4; static constexpr uint8_t NUM_OF_PARALLEL_COMMANDS = 4;
static constexpr uint16_t COMMAND_TIMEOUT_SECONDS = 60; static constexpr uint16_t COMMAND_TIMEOUT_SECONDS = 60;
Service3Housekeeping(object_id_t objectId, uint16_t apid, uint8_t serviceId); Service3Housekeeping(object_id_t objectId, uint16_t apid, uint8_t serviceId, uint32_t queueDepth,
uint8_t numParallelCommands);
virtual ~Service3Housekeeping(); virtual ~Service3Housekeeping();
protected: protected:

View File

@ -13,8 +13,10 @@ Service5EventReporting::Service5EventReporting(PsbParams params, size_t maxNumbe
storeHelper(params.apid), storeHelper(params.apid),
tmHelper(params.serviceId, storeHelper, sendHelper), tmHelper(params.serviceId, storeHelper, sendHelper),
maxNumberReportsPerCycle(maxNumberReportsPerCycle) { maxNumberReportsPerCycle(maxNumberReportsPerCycle) {
auto mqArgs = MqArgs(getObjectId(), static_cast<void*>(this));
psbParams.name = "PUS 5 Event Reporting"; psbParams.name = "PUS 5 Event Reporting";
eventQueue = QueueFactory::instance()->createMessageQueue(messageQueueDepth); eventQueue = QueueFactory::instance()->createMessageQueue(
messageQueueDepth, MessageQueueMessage::MAX_MESSAGE_SIZE, &mqArgs);
} }
Service5EventReporting::~Service5EventReporting() { Service5EventReporting::~Service5EventReporting() {
@ -38,9 +40,6 @@ ReturnValue_t Service5EventReporting::performService() {
} }
} }
} }
#if FSFW_CPP_OSTREAM_ENABLED == 1
sif::warning << "Service5EventReporting::generateEventReport: Too many events" << std::endl;
#endif
return returnvalue::OK; return returnvalue::OK;
} }

View File

@ -42,7 +42,7 @@
class Service5EventReporting : public PusServiceBase { class Service5EventReporting : public PusServiceBase {
public: public:
Service5EventReporting(PsbParams params, size_t maxNumberReportsPerCycle = 10, Service5EventReporting(PsbParams params, size_t maxNumberReportsPerCycle = 10,
uint32_t messageQueueDepth = 10); uint32_t messageQueueDepth = 20);
~Service5EventReporting() override; ~Service5EventReporting() override;
/*** /***

View File

@ -9,11 +9,11 @@
#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/serviceinterface/ServiceInterface.h"
Service8FunctionManagement::Service8FunctionManagement(object_id_t objectId, uint16_t apid, Service8FunctionManagement::Service8FunctionManagement(object_id_t objectId, uint16_t apid,
uint8_t serviceId, uint8_t serviceId, size_t queueDepth,
uint8_t numParallelCommands, uint8_t numParallelCommands,
uint16_t commandTimeoutSeconds) uint16_t commandTimeoutSeconds)
: CommandingServiceBase(objectId, apid, "PUS 8 Functional Commanding", serviceId, : CommandingServiceBase(objectId, apid, "PUS 8 Functional Commanding", serviceId,
numParallelCommands, commandTimeoutSeconds) {} numParallelCommands, commandTimeoutSeconds, queueDepth) {}
Service8FunctionManagement::~Service8FunctionManagement() {} Service8FunctionManagement::~Service8FunctionManagement() {}

View File

@ -31,7 +31,8 @@
class Service8FunctionManagement : public CommandingServiceBase { class Service8FunctionManagement : public CommandingServiceBase {
public: public:
Service8FunctionManagement(object_id_t objectId, uint16_t apid, uint8_t serviceId, Service8FunctionManagement(object_id_t objectId, uint16_t apid, uint8_t serviceId,
uint8_t numParallelCommands = 4, uint16_t commandTimeoutSeconds = 60); size_t queueDepth, uint8_t numParallelCommands = 4,
uint16_t commandTimeoutSeconds = 60);
~Service8FunctionManagement() override; ~Service8FunctionManagement() override;
protected: protected:

View File

@ -1,9 +1,9 @@
#ifndef FSFW_PUS_SERVICEPACKETS_SERVICE200PACKETS_H_ #ifndef FSFW_PUS_SERVICEPACKETS_SERVICE200PACKETS_H_
#define FSFW_PUS_SERVICEPACKETS_SERVICE200PACKETS_H_ #define FSFW_PUS_SERVICEPACKETS_SERVICE200PACKETS_H_
#include "../../modes/ModeMessage.h" #include "fsfw/modes/ModeMessage.h"
#include "../../serialize/SerialLinkedListAdapter.h" #include "fsfw/serialize/SerialLinkedListAdapter.h"
#include "../../serialize/SerializeIF.h" #include "fsfw/serialize/SerializeIF.h"
/** /**
* @brief Subservice 1, 2, 3, 4, 5 * @brief Subservice 1, 2, 3, 4, 5

View File

@ -3,14 +3,14 @@
#include "fsfw/FSFW.h" #include "fsfw/FSFW.h"
PoolManager::PoolManager(object_id_t setObjectId, const LocalPoolConfig& localPoolConfig) PoolManager::PoolManager(object_id_t setObjectId, const LocalPoolConfig& localPoolConfig)
: LocalPool(setObjectId, localPoolConfig, true) { : LocalPool(setObjectId, localPoolConfig, true, true) {
mutex = MutexFactory::instance()->createMutex(); mutex = MutexFactory::instance()->createMutex();
} }
PoolManager::~PoolManager() { MutexFactory::instance()->deleteMutex(mutex); } PoolManager::~PoolManager() { MutexFactory::instance()->deleteMutex(mutex); }
ReturnValue_t PoolManager::reserveSpace(const size_t size, store_address_t* address) { ReturnValue_t PoolManager::reserveSpace(const size_t size, store_address_t* address) {
MutexGuard mutexHelper(mutex, MutexIF::TimeoutType::WAITING, mutexTimeoutMs); MutexGuard mutexHelper(mutex, MutexIF::TimeoutType::WAITING, mutexTimeoutMs, LOCK_CTX);
ReturnValue_t status = LocalPool::reserveSpace(size, address); ReturnValue_t status = LocalPool::reserveSpace(size, address);
return status; return status;
} }
@ -22,12 +22,12 @@ ReturnValue_t PoolManager::deleteData(store_address_t storeId) {
<< storeId.poolIndex << ". id is " << storeId.packetIndex << std::endl; << storeId.poolIndex << ". id is " << storeId.packetIndex << std::endl;
#endif #endif
#endif #endif
MutexGuard mutexHelper(mutex, MutexIF::TimeoutType::WAITING, mutexTimeoutMs); MutexGuard mutexHelper(mutex, MutexIF::TimeoutType::WAITING, mutexTimeoutMs, LOCK_CTX);
return LocalPool::deleteData(storeId); return LocalPool::deleteData(storeId);
} }
ReturnValue_t PoolManager::deleteData(uint8_t* buffer, size_t size, store_address_t* storeId) { ReturnValue_t PoolManager::deleteData(uint8_t* buffer, size_t size, store_address_t* storeId) {
MutexGuard mutexHelper(mutex, MutexIF::TimeoutType::WAITING, 20); MutexGuard mutexHelper(mutex, MutexIF::TimeoutType::WAITING, mutexTimeoutMs, LOCK_CTX);
ReturnValue_t status = LocalPool::deleteData(buffer, size, storeId); ReturnValue_t status = LocalPool::deleteData(buffer, size, storeId);
return status; return status;
} }

View File

@ -56,6 +56,7 @@ class PoolManager : public LocalPool {
protected: protected:
//! Default mutex timeout value to prevent permanent blocking. //! Default mutex timeout value to prevent permanent blocking.
uint32_t mutexTimeoutMs = 20; uint32_t mutexTimeoutMs = 20;
static constexpr char LOCK_CTX[] = "PoolManager";
ReturnValue_t reserveSpace(size_t size, store_address_t* address) override; ReturnValue_t reserveSpace(size_t size, store_address_t* address) override;

View File

@ -1,3 +1,4 @@
target_sources(${LIB_FSFW_NAME} PRIVATE Subsystem.cpp SubsystemBase.cpp) target_sources(${LIB_FSFW_NAME} PRIVATE Subsystem.cpp SubsystemBase.cpp
helper.cpp)
add_subdirectory(modes) add_subdirectory(modes)

View File

@ -0,0 +1,13 @@
#ifndef FSFW_SUBSYSTEM_HASMODETREECHILDRENIF_H_
#define FSFW_SUBSYSTEM_HASMODETREECHILDRENIF_H_
#include "ModeTreeChildIF.h"
class HasModeTreeChildrenIF {
public:
virtual ~HasModeTreeChildrenIF() = default;
virtual ReturnValue_t registerChild(const ModeTreeChildIF& child) = 0;
virtual MessageQueueId_t getCommandQueue() const = 0;
};
#endif // FSFW_SUBSYSTEM_HASMODETREECHILDRENIF_H_

View File

@ -0,0 +1,15 @@
#ifndef FSFW_SUBSYSTEM_MODETREECHILDIF_H_
#define FSFW_SUBSYSTEM_MODETREECHILDIF_H_
#include <fsfw/health/HasHealthIF.h>
#include <fsfw/modes/HasModesIF.h>
class ModeTreeChildIF {
public:
virtual ~ModeTreeChildIF() = default;
virtual object_id_t getObjectId() const = 0;
virtual const HasHealthIF* getOptHealthIF() const = 0;
virtual const HasModesIF& getModeIF() const = 0;
};
#endif /* FSFW_SUBSYSTEM_MODETREECHILDIF_H_ */

View File

@ -0,0 +1,13 @@
#ifndef FSFW_SUBSYSTEM_MODES_MODETREECONNECTIONIF_H_
#define FSFW_SUBSYSTEM_MODES_MODETREECONNECTIONIF_H_
#include "fsfw/subsystem/HasModeTreeChildrenIF.h"
class ModeTreeConnectionIF {
public:
virtual ~ModeTreeConnectionIF() = default;
virtual ReturnValue_t connectModeTreeParent(HasModeTreeChildrenIF& parent) = 0;
virtual ModeTreeChildIF& getModeTreeChildIF() = 0;
};
#endif /* FSFW_SRC_FSFW_SUBSYSTEM_MODES_MODETREECONNECTIONIF_H_ */

View File

@ -9,9 +9,9 @@
#include "fsfw/serialize/SerialLinkedListAdapter.h" #include "fsfw/serialize/SerialLinkedListAdapter.h"
#include "fsfw/serialize/SerializeElement.h" #include "fsfw/serialize/SerializeElement.h"
Subsystem::Subsystem(object_id_t setObjectId, object_id_t parent, uint32_t maxNumberOfSequences, Subsystem::Subsystem(object_id_t setObjectId, uint32_t maxNumberOfSequences,
uint32_t maxNumberOfTables) uint32_t maxNumberOfTables)
: SubsystemBase(setObjectId, parent, 0), : SubsystemBase(setObjectId, 0),
isInTransition(false), isInTransition(false),
childrenChangedHealth(false), childrenChangedHealth(false),
currentTargetTable(), currentTargetTable(),
@ -36,6 +36,13 @@ ReturnValue_t Subsystem::checkSequence(HybridIterator<ModeListEntry> iter,
for (; iter.value != nullptr; ++iter) { for (; iter.value != nullptr; ++iter) {
if (!existsModeTable(iter->getTableId())) { if (!existsModeTable(iter->getTableId())) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
using namespace std;
sif::warning << "Subsystem::checkSequence: "
<< "Object " << setfill('0') << hex << "0x" << setw(8) << getObjectId()
<< setw(0) << ": Mode table for mode ID "
<< "0x" << setw(8) << iter->getTableId() << " does not exist" << dec << endl;
#endif
return TABLE_DOES_NOT_EXIST; return TABLE_DOES_NOT_EXIST;
} else { } else {
ReturnValue_t result = checkTable(getTable(iter->getTableId())); ReturnValue_t result = checkTable(getTable(iter->getTableId()));

View File

@ -33,8 +33,12 @@ struct SequenceEntry : public TableSequenceBase {
}; };
/** /**
* @brief TODO: documentation missing * @brief This class extends the SubsystemBase to perform the management of mode tables
* and mode sequences
* @details * @details
* This class is able to use mode tables and sequences to command all its children into the
* right mode. Fallback sequences can be used to handle failed transitions or have a fallback
* in case a component can't keep its current mode.
*/ */
class Subsystem : public SubsystemBase, public HasModeSequenceIF { class Subsystem : public SubsystemBase, public HasModeSequenceIF {
public: public:
@ -62,8 +66,7 @@ class Subsystem : public SubsystemBase, public HasModeSequenceIF {
* @param maxNumberOfSequences * @param maxNumberOfSequences
* @param maxNumberOfTables * @param maxNumberOfTables
*/ */
Subsystem(object_id_t setObjectId, object_id_t parent, uint32_t maxNumberOfSequences, Subsystem(object_id_t setObjectId, uint32_t maxNumberOfSequences, uint32_t maxNumberOfTables);
uint32_t maxNumberOfTables);
virtual ~Subsystem(); virtual ~Subsystem();
ReturnValue_t addSequence(SequenceEntry sequence); ReturnValue_t addSequence(SequenceEntry sequence);

View File

@ -1,52 +1,27 @@
#include "fsfw/subsystem/SubsystemBase.h" #include "fsfw/subsystem/SubsystemBase.h"
#include "fsfw/FSFW.h"
#include "fsfw/ipc/QueueFactory.h" #include "fsfw/ipc/QueueFactory.h"
#include "fsfw/objectmanager/ObjectManager.h" #include "fsfw/objectmanager/ObjectManager.h"
#include "fsfw/serviceinterface/ServiceInterface.h" #include "fsfw/serviceinterface.h"
#include "fsfw/subsystem/helper.h"
SubsystemBase::SubsystemBase(object_id_t setObjectId, object_id_t parent, Mode_t initialMode, SubsystemBase::SubsystemBase(object_id_t setObjectId, Mode_t initialMode,
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) {} 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); }
ReturnValue_t SubsystemBase::registerChild(object_id_t objectId) {
ChildInfo info;
HasModesIF* child = ObjectManager::instance()->get<HasModesIF>(objectId);
// This is a rather ugly hack to have the changedHealth info for all
// children available.
HasHealthIF* healthChild = ObjectManager::instance()->get<HasHealthIF>(objectId);
if (child == nullptr) {
if (healthChild == nullptr) {
return CHILD_DOESNT_HAVE_MODES;
} else {
info.commandQueue = healthChild->getCommandQueue();
info.mode = MODE_OFF;
}
} else {
info.commandQueue = child->getCommandQueue();
info.mode = -1; // intentional to force an initial command during system startup
}
info.submode = SUBMODE_NONE;
info.healthChanged = false;
auto resultPair = childrenMap.emplace(objectId, info);
if (not resultPair.second) {
return COULD_NOT_INSERT_CHILD;
}
return returnvalue::OK;
}
ReturnValue_t SubsystemBase::checkStateAgainstTable(HybridIterator<ModeListEntry> tableIter, ReturnValue_t SubsystemBase::checkStateAgainstTable(HybridIterator<ModeListEntry> tableIter,
Submode_t targetSubmode) { Submode_t targetSubmode) {
using namespace mode;
std::map<object_id_t, ChildInfo>::iterator childIter; std::map<object_id_t, ChildInfo>::iterator childIter;
for (; tableIter.value != NULL; ++tableIter) { for (; tableIter.value != NULL; ++tableIter) {
@ -60,13 +35,21 @@ ReturnValue_t SubsystemBase::checkStateAgainstTable(HybridIterator<ModeListEntry
return returnvalue::FAILED; return returnvalue::FAILED;
} }
Submode_t submodeToCheckAgainst = tableIter.value->getSubmode(); // Check submodes here.
uint8_t mask;
bool submodesAllowedMask = tableIter.value->submodesAllowed(&mask);
uint8_t submodeToCheckAgainst = tableIter.value->getSubmode();
if (tableIter.value->inheritSubmode()) { if (tableIter.value->inheritSubmode()) {
submodeToCheckAgainst = targetSubmode; submodeToCheckAgainst = targetSubmode;
} }
if (submodesAllowedMask) {
if (childIter->second.submode != submodeToCheckAgainst) { if ((childIter->second.submode | mask) != mask) {
return returnvalue::FAILED; return returnvalue::FAILED;
}
} else {
if (childIter->second.submode != submodeToCheckAgainst) {
return returnvalue::FAILED;
}
} }
} }
return returnvalue::OK; return returnvalue::OK;
@ -84,7 +67,8 @@ void SubsystemBase::executeTable(HybridIterator<ModeListEntry> tableIter, Submod
if ((iter = childrenMap.find(object)) == childrenMap.end()) { if ((iter = childrenMap.find(object)) == childrenMap.end()) {
// illegal table entry, should only happen due to misconfigured mode table // illegal table entry, should only happen due to misconfigured mode table
#if FSFW_CPP_OSTREAM_ENABLED == 1 #if FSFW_CPP_OSTREAM_ENABLED == 1
sif::debug << std::hex << getObjectId() << ": invalid mode table entry" << std::endl; sif::debug << std::hex << SystemObject::getObjectId() << ": invalid mode table entry"
<< std::endl;
#endif #endif
continue; continue;
} }
@ -142,6 +126,20 @@ ReturnValue_t SubsystemBase::updateChildMode(MessageQueueId_t queue, Mode_t mode
return CHILD_NOT_FOUND; return CHILD_NOT_FOUND;
} }
ReturnValue_t SubsystemBase::updateChildModeByObjId(object_id_t objectId, Mode_t mode,
Submode_t submode) {
std::map<object_id_t, ChildInfo>::iterator iter;
for (iter = childrenMap.begin(); iter != childrenMap.end(); iter++) {
if (iter->first == objectId) {
iter->second.mode = mode;
iter->second.submode = submode;
return returnvalue::OK;
}
}
return CHILD_NOT_FOUND;
}
ReturnValue_t SubsystemBase::updateChildChangedHealth(MessageQueueId_t queue, bool changedHealth) { ReturnValue_t SubsystemBase::updateChildChangedHealth(MessageQueueId_t queue, bool changedHealth) {
for (auto iter = childrenMap.begin(); iter != childrenMap.end(); iter++) { for (auto iter = childrenMap.begin(); iter != childrenMap.end(); iter++) {
if (iter->second.commandQueue == queue) { if (iter->second.commandQueue == queue) {
@ -155,36 +153,15 @@ ReturnValue_t SubsystemBase::updateChildChangedHealth(MessageQueueId_t queue, bo
MessageQueueId_t SubsystemBase::getCommandQueue() const { return commandQueue->getId(); } MessageQueueId_t SubsystemBase::getCommandQueue() const { return commandQueue->getId(); }
ReturnValue_t SubsystemBase::initialize() { ReturnValue_t SubsystemBase::initialize() {
MessageQueueId_t parentQueue = MessageQueueIF::NO_QUEUE; ReturnValue_t result = modeHelper.initialize();
ReturnValue_t result = SystemObject::initialize();
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
return result; return result;
} }
result = healthHelper.initialize();
if (parentId != objects::NO_OBJECT) {
SubsystemBase* parent = ObjectManager::instance()->get<SubsystemBase>(parentId);
if (parent == nullptr) {
return returnvalue::FAILED;
}
parentQueue = parent->getCommandQueue();
parent->registerChild(getObjectId());
}
result = healthHelper.initialize(parentQueue);
if (result != returnvalue::OK) { if (result != returnvalue::OK) {
return result; return result;
} }
return SystemObject::initialize();
result = modeHelper.initialize(parentQueue);
if (result != returnvalue::OK) {
return result;
}
return returnvalue::OK;
} }
ReturnValue_t SubsystemBase::performOperation(uint8_t opCode) { ReturnValue_t SubsystemBase::performOperation(uint8_t opCode) {
@ -237,8 +214,14 @@ ReturnValue_t SubsystemBase::handleModeReply(CommandMessage* message) {
} }
ReturnValue_t SubsystemBase::checkTable(HybridIterator<ModeListEntry> tableIter) { ReturnValue_t SubsystemBase::checkTable(HybridIterator<ModeListEntry> tableIter) {
for (; tableIter.value != NULL; ++tableIter) { for (; tableIter.value != nullptr; ++tableIter) {
if (childrenMap.find(tableIter.value->getObject()) == childrenMap.end()) { if (childrenMap.find(tableIter.value->getObject()) == childrenMap.end()) {
#if FSFW_CPP_OSTREAM_ENABLED == 1
using namespace std;
sif::warning << "SubsystemBase::checkTable: Could not find object " << setfill('0') << hex
<< "0x" << setw(8) << tableIter.value->getObject() << " in object " << setw(8)
<< setw(0) << "0x" << setw(8) << SystemObject::getObjectId() << dec << std::endl;
#endif
return TABLE_CONTAINS_INVALID_OBJECT_ID; return TABLE_CONTAINS_INVALID_OBJECT_ID;
} }
} }
@ -323,4 +306,36 @@ ReturnValue_t SubsystemBase::setHealth(HealthState health) {
HasHealthIF::HealthState SubsystemBase::getHealth() { return healthHelper.getHealth(); } HasHealthIF::HealthState SubsystemBase::getHealth() { return healthHelper.getHealth(); }
ReturnValue_t SubsystemBase::connectModeTreeParent(HasModeTreeChildrenIF& parent) {
return modetree::connectModeTreeParent(parent, *this, &healthHelper, modeHelper);
}
object_id_t SubsystemBase::getObjectId() const { return SystemObject::getObjectId(); }
void SubsystemBase::modeChanged() {} void SubsystemBase::modeChanged() {}
ReturnValue_t SubsystemBase::registerChild(const ModeTreeChildIF& child) {
return registerChild(child.getObjectId(), child.getModeIF().getCommandQueue());
}
const HasHealthIF* SubsystemBase::getOptHealthIF() const { return this; }
const HasModesIF& SubsystemBase::getModeIF() const { return *this; }
ModeTreeChildIF& SubsystemBase::getModeTreeChildIF() { return *this; }
ReturnValue_t SubsystemBase::registerChild(object_id_t childObjectId, MessageQueueId_t childQueue) {
ChildInfo info;
// intentional to force an initial command during system startup
info.commandQueue = childQueue;
info.mode = HasModesIF::MODE_UNDEFINED;
info.submode = SUBMODE_NONE;
info.healthChanged = false;
auto resultPair = childrenMap.emplace(childObjectId, info);
if (not resultPair.second) {
return COULD_NOT_INSERT_CHILD;
}
return returnvalue::OK;
}

View File

@ -3,23 +3,35 @@
#include <map> #include <map>
#include "../container/HybridIterator.h" #include "fsfw/container/HybridIterator.h"
#include "../health/HasHealthIF.h" #include "fsfw/health/HasHealthIF.h"
#include "../health/HealthHelper.h" #include "fsfw/health/HealthHelper.h"
#include "../ipc/MessageQueueIF.h" #include "fsfw/ipc/MessageQueueIF.h"
#include "../modes/HasModesIF.h" #include "fsfw/modes/HasModesIF.h"
#include "../objectmanager/SystemObject.h" #include "fsfw/objectmanager/SystemObject.h"
#include "../returnvalues/returnvalue.h" #include "fsfw/returnvalues/returnvalue.h"
#include "../tasks/ExecutableObjectIF.h" #include "fsfw/subsystem/HasModeTreeChildrenIF.h"
#include "fsfw/subsystem/ModeTreeConnectionIF.h"
#include "fsfw/tasks/ExecutableObjectIF.h"
#include "modes/HasModeSequenceIF.h" #include "modes/HasModeSequenceIF.h"
/** /**
* @defgroup subsystems Subsystem Objects * @defgroup subsystems Subsystem Objects
* Contains all Subsystem and Assemblies * All Subsystem and Assemblies can derive from this class. It contains helper classes to
* perform mode and health handling, which allows OBSW developers to build a mode tree for
* the whole satellite.
*
* Aside from setting up a mode tree and being able to executing mode tables, this class does not
* provide an implementation on what to do with the features. To build a mode tree, helper classes
* like the #AssemblyBase or the #Subsystem class extend and use the functionality of the base
* class.
*/ */
class SubsystemBase : public SystemObject, class SubsystemBase : public SystemObject,
public HasModesIF, public HasModesIF,
public HasHealthIF, public HasHealthIF,
public HasModeTreeChildrenIF,
public ModeTreeConnectionIF,
public ModeTreeChildIF,
public ExecutableObjectIF { public ExecutableObjectIF {
public: public:
static const uint8_t INTERFACE_ID = CLASS_ID::SUBSYSTEM_BASE; static const uint8_t INTERFACE_ID = CLASS_ID::SUBSYSTEM_BASE;
@ -29,32 +41,36 @@ class SubsystemBase : public SystemObject,
static const ReturnValue_t COULD_NOT_INSERT_CHILD = MAKE_RETURN_CODE(0x04); static const ReturnValue_t COULD_NOT_INSERT_CHILD = MAKE_RETURN_CODE(0x04);
static const ReturnValue_t TABLE_CONTAINS_INVALID_OBJECT_ID = MAKE_RETURN_CODE(0x05); static const ReturnValue_t TABLE_CONTAINS_INVALID_OBJECT_ID = MAKE_RETURN_CODE(0x05);
SubsystemBase(object_id_t setObjectId, object_id_t parent, Mode_t initialMode = 0, SubsystemBase(object_id_t setObjectId, Mode_t initialMode = 0, uint16_t commandQueueDepth = 8);
uint16_t commandQueueDepth = 8);
virtual ~SubsystemBase(); virtual ~SubsystemBase();
virtual MessageQueueId_t getCommandQueue() const override; virtual MessageQueueId_t getCommandQueue() const override;
ReturnValue_t connectModeTreeParent(HasModeTreeChildrenIF &parent) override;
ModeTreeChildIF &getModeTreeChildIF() override;
/** /**
* Function to register the child objects. * Function to register the child objects.
* Performs a checks if the child does implement HasHealthIF and/or HasModesIF * Performs a checks if the child does implement HasHealthIF and/or HasModesIF
* *
* Also adds them to the internal childrenMap. * Also adds them to the internal childrenMap.
* *
* @param objectId * @param objectId
* @return returnvalue::OK if successful * @return returnvalue::OK if successful
* CHILD_DOESNT_HAVE_MODES if Child is no HasHealthIF and no HasModesIF * CHILD_DOESNT_HAVE_MODES if Child is no HasHealthIF and no HasModesIF
* COULD_NOT_INSERT_CHILD If the Child could not be added to the ChildrenMap * COULD_NOT_INSERT_CHILD If the Child could not be added to the ChildrenMap
*/ */
ReturnValue_t registerChild(object_id_t objectId); ReturnValue_t registerChild(const ModeTreeChildIF &child) override;
// TODO: Add this to HasModeTreeChildrenIF.
ReturnValue_t registerChild(object_id_t childObjectId, MessageQueueId_t childQueue);
virtual ReturnValue_t initialize() override; ReturnValue_t initialize() override;
virtual ReturnValue_t performOperation(uint8_t opCode) override; ReturnValue_t performOperation(uint8_t opCode) override;
virtual ReturnValue_t setHealth(HealthState health) override; ReturnValue_t setHealth(HealthState health) override;
virtual HasHealthIF::HealthState getHealth() override; HasHealthIF::HealthState getHealth() override;
protected: protected:
struct ChildInfo { struct ChildInfo {
@ -81,8 +97,6 @@ class SubsystemBase : public SystemObject,
ModeHelper modeHelper; ModeHelper modeHelper;
const object_id_t parentId;
typedef std::map<object_id_t, ChildInfo> ChildrenMap; typedef std::map<object_id_t, ChildInfo> ChildrenMap;
ChildrenMap childrenMap; ChildrenMap childrenMap;
@ -95,6 +109,7 @@ class SubsystemBase : public SystemObject,
Submode_t targetSubmode); Submode_t targetSubmode);
/** /**
* This function takes care of sending all according mode commands specified inside a mode table.
* We need to know the target Submode, as children are able to inherit the submode * We need to know the target Submode, as children are able to inherit the submode
* Still, we have a default for all child implementations which do not use submode inheritance * Still, we have a default for all child implementations which do not use submode inheritance
*/ */
@ -102,6 +117,7 @@ class SubsystemBase : public SystemObject,
Submode_t targetSubmode = SUBMODE_NONE); Submode_t targetSubmode = SUBMODE_NONE);
ReturnValue_t updateChildMode(MessageQueueId_t queue, Mode_t mode, Submode_t submode); ReturnValue_t updateChildMode(MessageQueueId_t queue, Mode_t mode, Submode_t submode);
ReturnValue_t updateChildModeByObjId(object_id_t objectId, Mode_t mode, Submode_t submode);
ReturnValue_t updateChildChangedHealth(MessageQueueId_t queue, bool changedHealth = true); ReturnValue_t updateChildChangedHealth(MessageQueueId_t queue, bool changedHealth = true);
@ -128,6 +144,10 @@ class SubsystemBase : public SystemObject,
virtual void getMode(Mode_t *mode, Submode_t *submode) override; virtual void getMode(Mode_t *mode, Submode_t *submode) override;
object_id_t getObjectId() const override;
const HasHealthIF *getOptHealthIF() const override;
const HasModesIF &getModeIF() const override;
virtual void setToExternalControl() override; virtual void setToExternalControl() override;
virtual void announceMode(bool recursive) override; virtual void announceMode(bool recursive) override;

View File

@ -0,0 +1,15 @@
#include "helper.h"
ReturnValue_t modetree::connectModeTreeParent(HasModeTreeChildrenIF& parent,
const ModeTreeChildIF& child,
HealthHelper* healthHelper, ModeHelper& modeHelper) {
ReturnValue_t result = parent.registerChild(child);
if (result != returnvalue::OK) {
return result;
}
if (healthHelper != nullptr) {
healthHelper->setParentQueue(parent.getCommandQueue());
}
modeHelper.setParentQueue(parent.getCommandQueue());
return returnvalue::OK;
}

View File

@ -0,0 +1,14 @@
#ifndef FSFW_SUBSYSTEM_HELPER_H_
#define FSFW_SUBSYSTEM_HELPER_H_
#include "HasModeTreeChildrenIF.h"
#include "fsfw/health/HealthHelper.h"
namespace modetree {
ReturnValue_t connectModeTreeParent(HasModeTreeChildrenIF& parent, const ModeTreeChildIF& child,
HealthHelper* healthHelper, ModeHelper& modeHelper);
}
#endif /* FSFW_SRC_FSFW_SUBSYSTEM_HELPER_H_ */

Some files were not shown because too many files have changed in this diff Show More